Added ahal

This is a formatted copy of WPILib's default user-visible C++ API, with
a bit of completely unnecessary functionality stripped out. Most of the
stripping so far is only related to weird threading decisions.

Change-Id: Icbfd949b48cd115561862cb909bcc572aba0e753
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/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..4686b68 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",
         ],
     ),
diff --git a/third_party/allwpilib_2018/BUILD b/third_party/allwpilib_2018/BUILD
index 38d9559..54e63da 100644
--- a/third_party/allwpilib_2018/BUILD
+++ b/third_party/allwpilib_2018/BUILD
@@ -1,143 +1,65 @@
-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__"],
+    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/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 2b0edb5..52b7c6a 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"
@@ -56,6 +56,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));