Squashed 'third_party/allwpilib_2017/' content from commit 35ac87d

Change-Id: I7bb6f5556c30d3f5a092e68de0be9c710c60c9f4
git-subtree-dir: third_party/allwpilib_2017
git-subtree-split: 35ac87d6ff8b7f061c4f18c9ea316e5dccd4888a
diff --git a/wpilibc/athena/include/ADXL345_I2C.h b/wpilibc/athena/include/ADXL345_I2C.h
new file mode 100644
index 0000000..9f29592
--- /dev/null
+++ b/wpilibc/athena/include/ADXL345_I2C.h
@@ -0,0 +1,87 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "I2C.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "interfaces/Accelerometer.h"
+
+namespace frc {
+
+/**
+ * ADXL345 Accelerometer on I2C.
+ *
+ * This class allows access to a Analog Devices ADXL345 3-axis accelerometer on
+ * an I2C bus.
+ * This class assumes the default (not alternate) sensor address of 0x1D (7-bit
+ * address).
+ */
+class ADXL345_I2C : public Accelerometer, public LiveWindowSendable {
+ protected:
+  static const int kAddress = 0x1D;
+  static const int kPowerCtlRegister = 0x2D;
+  static const int kDataFormatRegister = 0x31;
+  static const int kDataRegister = 0x32;
+  static constexpr double kGsPerLSB = 0.00390625;
+  enum PowerCtlFields {
+    kPowerCtl_Link = 0x20,
+    kPowerCtl_AutoSleep = 0x10,
+    kPowerCtl_Measure = 0x08,
+    kPowerCtl_Sleep = 0x04
+  };
+  enum DataFormatFields {
+    kDataFormat_SelfTest = 0x80,
+    kDataFormat_SPI = 0x40,
+    kDataFormat_IntInvert = 0x20,
+    kDataFormat_FullRes = 0x08,
+    kDataFormat_Justify = 0x04
+  };
+
+ public:
+  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
+  struct AllAxes {
+    double XAxis;
+    double YAxis;
+    double ZAxis;
+  };
+
+ public:
+  explicit ADXL345_I2C(I2C::Port port, Range range = kRange_2G,
+                       int deviceAddress = kAddress);
+  virtual ~ADXL345_I2C() = default;
+
+  ADXL345_I2C(const ADXL345_I2C&) = delete;
+  ADXL345_I2C& operator=(const ADXL345_I2C&) = delete;
+
+  // Accelerometer interface
+  void SetRange(Range range) override;
+  double GetX() override;
+  double GetY() override;
+  double GetZ() override;
+
+  virtual double GetAcceleration(Axes axis);
+  virtual AllAxes GetAccelerations();
+
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subtable) override;
+  void UpdateTable() override;
+  std::shared_ptr<ITable> GetTable() const override;
+  void StartLiveWindowMode() override {}
+  void StopLiveWindowMode() override {}
+
+ protected:
+  I2C m_i2c;
+
+ private:
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/ADXL345_SPI.h b/wpilibc/athena/include/ADXL345_SPI.h
new file mode 100644
index 0000000..73fe942
--- /dev/null
+++ b/wpilibc/athena/include/ADXL345_SPI.h
@@ -0,0 +1,89 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "LiveWindow/LiveWindowSendable.h"
+#include "SPI.h"
+#include "SensorBase.h"
+#include "interfaces/Accelerometer.h"
+
+namespace frc {
+
+class DigitalInput;
+class DigitalOutput;
+
+/**
+ * ADXL345 Accelerometer on SPI.
+ *
+ * This class allows access to an Analog Devices ADXL345 3-axis accelerometer
+ * via SPI.
+ * This class assumes the sensor is wired in 4-wire SPI mode.
+ */
+class ADXL345_SPI : public Accelerometer, public LiveWindowSendable {
+ protected:
+  static const int kPowerCtlRegister = 0x2D;
+  static const int kDataFormatRegister = 0x31;
+  static const int kDataRegister = 0x32;
+  static constexpr double kGsPerLSB = 0.00390625;
+  enum SPIAddressFields { kAddress_Read = 0x80, kAddress_MultiByte = 0x40 };
+  enum PowerCtlFields {
+    kPowerCtl_Link = 0x20,
+    kPowerCtl_AutoSleep = 0x10,
+    kPowerCtl_Measure = 0x08,
+    kPowerCtl_Sleep = 0x04
+  };
+  enum DataFormatFields {
+    kDataFormat_SelfTest = 0x80,
+    kDataFormat_SPI = 0x40,
+    kDataFormat_IntInvert = 0x20,
+    kDataFormat_FullRes = 0x08,
+    kDataFormat_Justify = 0x04
+  };
+
+ public:
+  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
+  struct AllAxes {
+    double XAxis;
+    double YAxis;
+    double ZAxis;
+  };
+
+ public:
+  explicit ADXL345_SPI(SPI::Port port, Range range = kRange_2G);
+  virtual ~ADXL345_SPI() = default;
+
+  ADXL345_SPI(const ADXL345_SPI&) = delete;
+  ADXL345_SPI& operator=(const ADXL345_SPI&) = delete;
+
+  // Accelerometer interface
+  void SetRange(Range range) override;
+  double GetX() override;
+  double GetY() override;
+  double GetZ() override;
+
+  virtual double GetAcceleration(Axes axis);
+  virtual AllAxes GetAccelerations();
+
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subtable) override;
+  void UpdateTable() override;
+  std::shared_ptr<ITable> GetTable() const override;
+  void StartLiveWindowMode() override {}
+  void StopLiveWindowMode() override {}
+
+ protected:
+  SPI m_spi;
+
+ private:
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/ADXL362.h b/wpilibc/athena/include/ADXL362.h
new file mode 100644
index 0000000..98c8ae2
--- /dev/null
+++ b/wpilibc/athena/include/ADXL362.h
@@ -0,0 +1,68 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "LiveWindow/LiveWindowSendable.h"
+#include "SPI.h"
+#include "SensorBase.h"
+#include "interfaces/Accelerometer.h"
+
+namespace frc {
+
+class DigitalInput;
+class DigitalOutput;
+
+/**
+ * ADXL362 SPI Accelerometer.
+ *
+ * This class allows access to an Analog Devices ADXL362 3-axis accelerometer.
+ */
+class ADXL362 : public Accelerometer, public LiveWindowSendable {
+ public:
+  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
+  struct AllAxes {
+    double XAxis;
+    double YAxis;
+    double ZAxis;
+  };
+
+ public:
+  explicit ADXL362(Range range = kRange_2G);
+  explicit ADXL362(SPI::Port port, Range range = kRange_2G);
+  virtual ~ADXL362() = default;
+
+  ADXL362(const ADXL362&) = delete;
+  ADXL362& operator=(const ADXL362&) = delete;
+
+  // Accelerometer interface
+  void SetRange(Range range) override;
+  double GetX() override;
+  double GetY() override;
+  double GetZ() override;
+
+  virtual double GetAcceleration(Axes axis);
+  virtual AllAxes GetAccelerations();
+
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subtable) override;
+  void UpdateTable() override;
+  std::shared_ptr<ITable> GetTable() const override;
+  void StartLiveWindowMode() override {}
+  void StopLiveWindowMode() override {}
+
+ private:
+  SPI m_spi;
+  double m_gsPerLSB = 0.001;
+
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/ADXRS450_Gyro.h b/wpilibc/athena/include/ADXRS450_Gyro.h
new file mode 100644
index 0000000..5c52f7e
--- /dev/null
+++ b/wpilibc/athena/include/ADXRS450_Gyro.h
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <memory>
+
+#include "GyroBase.h"
+#include "HAL/cpp/priority_mutex.h"
+#include "Notifier.h"
+#include "SPI.h"
+
+namespace frc {
+
+/**
+ * Use a rate gyro to return the robots heading relative to a starting position.
+ * The Gyro class tracks the robots heading based on the starting position. As
+ * the robot rotates the new heading is computed by integrating the rate of
+ * rotation returned by the sensor. When the class is instantiated, it does a
+ * short calibration routine where it samples the gyro while at rest to
+ * determine the default offset. This is subtracted from each sample to
+ * determine the heading.
+ *
+ * This class is for the digital ADXRS450 gyro sensor that connects via SPI.
+ */
+class ADXRS450_Gyro : public GyroBase {
+ public:
+  ADXRS450_Gyro();
+  explicit ADXRS450_Gyro(SPI::Port port);
+  virtual ~ADXRS450_Gyro() = default;
+
+  double GetAngle() const override;
+  double GetRate() const override;
+  void Reset() override;
+  void Calibrate() override;
+
+ private:
+  SPI m_spi;
+
+  uint16_t ReadRegister(int reg);
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/AnalogAccelerometer.h b/wpilibc/athena/include/AnalogAccelerometer.h
new file mode 100644
index 0000000..9f97032
--- /dev/null
+++ b/wpilibc/athena/include/AnalogAccelerometer.h
@@ -0,0 +1,57 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "AnalogInput.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "PIDSource.h"
+#include "SensorBase.h"
+
+namespace frc {
+
+/**
+ * Handle operation of an analog accelerometer.
+ * The accelerometer reads acceleration directly through the sensor. Many
+ * sensors have multiple axis and can be treated as multiple devices. Each is
+ * calibrated by finding the center value over a period of time.
+ */
+class AnalogAccelerometer : public SensorBase,
+                            public PIDSource,
+                            public LiveWindowSendable {
+ public:
+  explicit AnalogAccelerometer(int channel);
+  explicit AnalogAccelerometer(AnalogInput* channel);
+  explicit AnalogAccelerometer(std::shared_ptr<AnalogInput> channel);
+  virtual ~AnalogAccelerometer() = default;
+
+  double GetAcceleration() const;
+  void SetSensitivity(double sensitivity);
+  void SetZero(double zero);
+  double PIDGet() override;
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+ private:
+  void InitAccelerometer();
+
+  std::shared_ptr<AnalogInput> m_analogInput;
+  double m_voltsPerG = 1.0;
+  double m_zeroGVoltage = 2.5;
+
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/AnalogGyro.h b/wpilibc/athena/include/AnalogGyro.h
new file mode 100644
index 0000000..43fc7cf
--- /dev/null
+++ b/wpilibc/athena/include/AnalogGyro.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 "GyroBase.h"
+#include "HAL/Types.h"
+
+namespace frc {
+
+class AnalogInput;
+
+/**
+ * Use a rate gyro to return the robots heading relative to a starting position.
+ * The Gyro class tracks the robots heading based on the starting position. As
+ * the robot rotates the new heading is computed by integrating the rate of
+ * rotation returned by the sensor. When the class is instantiated, it does a
+ * short calibration routine where it samples the gyro while at rest to
+ * determine the default offset. This is subtracted from each sample to
+ * determine the heading. This gyro class must be used with a channel that is
+ * assigned one of the Analog accumulators from the FPGA. See AnalogInput for
+ * the current accumulator assignments.
+ *
+ * This class is for gyro sensors that connect to an analog input.
+ */
+class AnalogGyro : public GyroBase {
+ public:
+  static const int kOversampleBits = 10;
+  static const int kAverageBits = 0;
+  static constexpr double kSamplesPerSecond = 50.0;
+  static constexpr double kCalibrationSampleTime = 5.0;
+  static constexpr double kDefaultVoltsPerDegreePerSecond = 0.007;
+
+  explicit AnalogGyro(int channel);
+  explicit AnalogGyro(AnalogInput* channel);
+  explicit AnalogGyro(std::shared_ptr<AnalogInput> channel);
+  AnalogGyro(int channel, int center, double offset);
+  AnalogGyro(std::shared_ptr<AnalogInput> channel, int center, double offset);
+  virtual ~AnalogGyro();
+
+  double GetAngle() const override;
+  double GetRate() const override;
+  virtual int GetCenter() const;
+  virtual double GetOffset() const;
+  void SetSensitivity(double voltsPerDegreePerSecond);
+  void SetDeadband(double volts);
+  void Reset() override;
+  virtual void InitGyro();
+  void Calibrate() override;
+
+ protected:
+  std::shared_ptr<AnalogInput> m_analog;
+
+ private:
+  HAL_GyroHandle m_gyroHandle = HAL_kInvalidHandle;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/AnalogInput.h b/wpilibc/athena/include/AnalogInput.h
new file mode 100644
index 0000000..9353a9b
--- /dev/null
+++ b/wpilibc/athena/include/AnalogInput.h
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "LiveWindow/LiveWindowSendable.h"
+#include "PIDSource.h"
+#include "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 : public SensorBase,
+                    public PIDSource,
+                    public LiveWindowSendable {
+  friend class AnalogTrigger;
+  friend class AnalogGyro;
+
+ public:
+  static const int kAccumulatorModuleNumber = 1;
+  static const int kAccumulatorNumChannels = 2;
+  static const int kAccumulatorChannels[kAccumulatorNumChannels];
+
+  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;
+
+  bool IsAccumulatorChannel() const;
+  void InitAccumulator();
+  void SetAccumulatorInitialValue(int64_t value);
+  void ResetAccumulator();
+  void SetAccumulatorCenter(int center);
+  void SetAccumulatorDeadband(int deadband);
+  int64_t GetAccumulatorValue() const;
+  int64_t GetAccumulatorCount() const;
+  void GetAccumulatorOutput(int64_t& value, int64_t& count) const;
+
+  static void SetSampleRate(double samplesPerSecond);
+  static double GetSampleRate();
+
+  double PIDGet() override;
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+ private:
+  int m_channel;
+  // TODO: Adjust HAL to avoid use of raw pointers.
+  HAL_AnalogInputHandle m_port;
+  int64_t m_accumulatorOffset;
+
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/AnalogOutput.h b/wpilibc/athena/include/AnalogOutput.h
new file mode 100644
index 0000000..ea0c819
--- /dev/null
+++ b/wpilibc/athena/include/AnalogOutput.h
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <stdint.h>
+
+#include <memory>
+#include <string>
+
+#include "HAL/AnalogOutput.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "SensorBase.h"
+
+namespace frc {
+
+/**
+ * MXP analog output class.
+ */
+class AnalogOutput : public SensorBase, public LiveWindowSendable {
+ public:
+  explicit AnalogOutput(int channel);
+  virtual ~AnalogOutput();
+
+  void SetVoltage(double voltage);
+  double GetVoltage() const;
+  int GetChannel();
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+ protected:
+  int m_channel;
+  HAL_AnalogOutputHandle m_port;
+
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/AnalogPotentiometer.h b/wpilibc/athena/include/AnalogPotentiometer.h
new file mode 100644
index 0000000..2f2360c
--- /dev/null
+++ b/wpilibc/athena/include/AnalogPotentiometer.h
@@ -0,0 +1,96 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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 "AnalogInput.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "interfaces/Potentiometer.h"
+
+namespace frc {
+
+/**
+ * Class for reading analog potentiometers. Analog potentiometers read
+ * in an analog voltage that corresponds to a position. The position is
+ * in whichever units you choose, by way of the scaling and offset
+ * constants passed to the constructor.
+ */
+class AnalogPotentiometer : public Potentiometer, public LiveWindowSendable {
+ public:
+  /**
+   * AnalogPotentiometer constructor.
+   *
+   * Use the fullRange and offset values so that the output produces
+   * meaningful values. I.E: you have a 270 degree potentiometer and
+   * you want the output to be degrees with the halfway point as 0
+   * degrees. The fullRange value is 270.0(degrees) and the offset is
+   * -135.0 since the halfway point after scaling is 135 degrees.
+   *
+   * This will calculate the result from the fullRange times the
+   * fraction of the supply voltage, plus the offset.
+   *
+   * @param channel The analog channel this potentiometer is plugged into.
+   * @param fullRange The scaling to multiply the voltage by to get a meaningful
+   * unit.
+   * @param offset The offset to add to the scaled value for controlling the
+   * zero value
+   */
+  explicit AnalogPotentiometer(int channel, double fullRange = 1.0,
+                               double offset = 0.0);
+
+  explicit AnalogPotentiometer(AnalogInput* input, double fullRange = 1.0,
+                               double offset = 0.0);
+
+  explicit AnalogPotentiometer(std::shared_ptr<AnalogInput> input,
+                               double fullRange = 1.0, double offset = 0.0);
+
+  virtual ~AnalogPotentiometer() = default;
+
+  /**
+   * Get the current reading of the potentiomer.
+   *
+   * @return The current position of the potentiometer.
+   */
+  double Get() const override;
+
+  /**
+   * Implement the PIDSource interface.
+   *
+   * @return The current reading.
+   */
+  double PIDGet() override;
+
+  /*
+   * Live Window code, only does anything if live window is activated.
+   */
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subtable) override;
+  void UpdateTable() override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+  /**
+   * AnalogPotentiometers don't have to do anything special when entering the
+   * LiveWindow.
+   */
+  void StartLiveWindowMode() override {}
+
+  /**
+   * AnalogPotentiometers don't have to do anything special when exiting the
+   * LiveWindow.
+   */
+  void StopLiveWindowMode() override {}
+
+ private:
+  std::shared_ptr<AnalogInput> m_analog_input;
+  double m_fullRange, m_offset;
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/AnalogTrigger.h b/wpilibc/athena/include/AnalogTrigger.h
new file mode 100644
index 0000000..90bbc05
--- /dev/null
+++ b/wpilibc/athena/include/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 "AnalogTriggerOutput.h"
+#include "HAL/Types.h"
+#include "SensorBase.h"
+
+namespace frc {
+
+class AnalogInput;
+
+class AnalogTrigger : public SensorBase {
+  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/wpilibc/athena/include/AnalogTriggerOutput.h b/wpilibc/athena/include/AnalogTriggerOutput.h
new file mode 100644
index 0000000..0ab932a
--- /dev/null
+++ b/wpilibc/athena/include/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 "DigitalSource.h"
+#include "HAL/AnalogTrigger.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/wpilibc/athena/include/AnalogTriggerType.h b/wpilibc/athena/include/AnalogTriggerType.h
new file mode 100644
index 0000000..9105e99
--- /dev/null
+++ b/wpilibc/athena/include/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/wpilibc/athena/include/BuiltInAccelerometer.h b/wpilibc/athena/include/BuiltInAccelerometer.h
new file mode 100644
index 0000000..f1cf030
--- /dev/null
+++ b/wpilibc/athena/include/BuiltInAccelerometer.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "LiveWindow/LiveWindowSendable.h"
+#include "SensorBase.h"
+#include "interfaces/Accelerometer.h"
+
+namespace frc {
+
+/**
+ * Built-in accelerometer.
+ *
+ * This class allows access to the roboRIO's internal accelerometer.
+ */
+class BuiltInAccelerometer : public Accelerometer,
+                             public SensorBase,
+                             public LiveWindowSendable {
+ public:
+  explicit BuiltInAccelerometer(Range range = kRange_8G);
+  virtual ~BuiltInAccelerometer() = default;
+
+  // Accelerometer interface
+  void SetRange(Range range) override;
+  double GetX() override;
+  double GetY() override;
+  double GetZ() override;
+
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subtable) override;
+  void UpdateTable() override;
+  std::shared_ptr<ITable> GetTable() const override;
+  void StartLiveWindowMode() override {}
+  void StopLiveWindowMode() override {}
+
+ private:
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/CANSpeedController.h b/wpilibc/athena/include/CANSpeedController.h
new file mode 100644
index 0000000..a0f31ad
--- /dev/null
+++ b/wpilibc/athena/include/CANSpeedController.h
@@ -0,0 +1,104 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SpeedController.h"
+
+namespace frc {
+
+/**
+ * Interface for "smart" CAN-based speed controllers.
+ */
+class CANSpeedController : public SpeedController {
+ public:
+  enum ControlMode {
+    kPercentVbus = 0,
+    kCurrent = 1,
+    kSpeed = 2,
+    kPosition = 3,
+    kVoltage = 4,
+    kFollower = 5,
+    kMotionProfile = 6,
+  };
+
+  // Helper function for the ControlMode enum
+  virtual bool IsModePID(ControlMode mode) const = 0;
+
+  enum Faults {
+    kCurrentFault = 1,
+    kTemperatureFault = 2,
+    kBusVoltageFault = 4,
+    kGateDriverFault = 8,
+    /* SRX extensions */
+    kFwdLimitSwitch = 0x10,
+    kRevLimitSwitch = 0x20,
+    kFwdSoftLimit = 0x40,
+    kRevSoftLimit = 0x80,
+  };
+
+  enum Limits { kForwardLimit = 1, kReverseLimit = 2 };
+
+  enum NeutralMode {
+    /** Use the NeutralMode that is set by the jumper wire on the CAN device */
+    kNeutralMode_Jumper = 0,
+    /** Stop the motor's rotation by applying a force. */
+    kNeutralMode_Brake = 1,
+    /** Do not attempt to stop the motor. Instead allow it to coast to a stop
+       without applying resistance. */
+    kNeutralMode_Coast = 2
+  };
+
+  enum LimitMode {
+    /** Only use switches for limits */
+    kLimitMode_SwitchInputsOnly = 0,
+    /** Use both switches and soft limits */
+    kLimitMode_SoftPositionLimits = 1,
+    /* SRX extensions */
+    /** Disable switches and disable soft limits */
+    kLimitMode_SrxDisableSwitchInputs = 2,
+  };
+
+  virtual double Get() const = 0;
+  virtual void Set(double value) = 0;
+  virtual void StopMotor() = 0;
+  virtual void Disable() = 0;
+  virtual void SetP(double p) = 0;
+  virtual void SetI(double i) = 0;
+  virtual void SetD(double d) = 0;
+  virtual void SetPID(double p, double i, double d) = 0;
+  virtual double GetP() const = 0;
+  virtual double GetI() const = 0;
+  virtual double GetD() const = 0;
+  virtual double GetBusVoltage() const = 0;
+  virtual double GetOutputVoltage() const = 0;
+  virtual double GetOutputCurrent() const = 0;
+  virtual double GetTemperature() const = 0;
+  virtual double GetPosition() const = 0;
+  virtual double GetSpeed() const = 0;
+  virtual bool GetForwardLimitOK() const = 0;
+  virtual bool GetReverseLimitOK() const = 0;
+  virtual uint16_t GetFaults() const = 0;
+  virtual void SetVoltageRampRate(double rampRate) = 0;
+  virtual int GetFirmwareVersion() const = 0;
+  virtual void ConfigNeutralMode(NeutralMode mode) = 0;
+  virtual void ConfigEncoderCodesPerRev(uint16_t codesPerRev) = 0;
+  virtual void ConfigPotentiometerTurns(uint16_t turns) = 0;
+  virtual void ConfigSoftPositionLimits(double forwardLimitPosition,
+                                        double reverseLimitPosition) = 0;
+  virtual void DisableSoftPositionLimits() = 0;
+  virtual void ConfigLimitMode(LimitMode mode) = 0;
+  virtual void ConfigForwardLimit(double forwardLimitPosition) = 0;
+  virtual void ConfigReverseLimit(double reverseLimitPosition) = 0;
+  virtual void ConfigMaxOutputVoltage(double voltage) = 0;
+  virtual void ConfigFaultTime(double faultTime) = 0;
+  // Hold off on interface until we figure out ControlMode enums.
+  // virtual void SetControlMode(ControlMode mode) = 0;
+  // virtual ControlMode GetControlMode() const = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/CameraServer.h b/wpilibc/athena/include/CameraServer.h
new file mode 100644
index 0000000..5dde767
--- /dev/null
+++ b/wpilibc/athena/include/CameraServer.h
@@ -0,0 +1,312 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <atomic>
+#include <memory>
+#include <mutex>
+#include <string>
+#include <vector>
+
+#include "ErrorBase.h"
+#include "cscore.h"
+#include "llvm/DenseMap.h"
+#include "llvm/StringMap.h"
+#include "llvm/StringRef.h"
+#include "networktables/NetworkTable.h"
+
+namespace frc {
+
+/**
+ * Singleton class for creating and keeping camera servers.
+ * Also publishes camera information to NetworkTables.
+ */
+class CameraServer : public ErrorBase {
+ public:
+  static constexpr uint16_t kBasePort = 1181;
+  static constexpr int kSize640x480 = 0;
+  static constexpr int kSize320x240 = 1;
+  static constexpr int kSize160x120 = 2;
+
+  /**
+   * Get the CameraServer instance.
+   */
+  static CameraServer* GetInstance();
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * <p>You should call this method to see a camera feed on the dashboard.
+   * If you also want to perform vision processing on the roboRIO, use
+   * getVideo() to get access to the camera images.
+   *
+   * The first time this overload is called, it calls
+   * {@link #StartAutomaticCapture(int)} with device 0, creating a camera
+   * named "USB Camera 0".  Subsequent calls increment the device number
+   * (e.g. 1, 2, etc).
+   */
+  cs::UsbCamera StartAutomaticCapture();
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * <p>This overload calls {@link #StartAutomaticCapture(String, int)} with
+   * a name of "USB Camera {dev}".
+   *
+   * @param dev The device number of the camera interface
+   */
+  cs::UsbCamera StartAutomaticCapture(int dev);
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * @param name The name to give the camera
+   * @param dev The device number of the camera interface
+   */
+  cs::UsbCamera StartAutomaticCapture(llvm::StringRef name, int dev);
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * @param name The name to give the camera
+   * @param path The device path (e.g. "/dev/video0") of the camera
+   */
+  cs::UsbCamera StartAutomaticCapture(llvm::StringRef name,
+                                      llvm::StringRef path);
+
+  /**
+   * Start automatically capturing images to send to the dashboard from
+   * an existing camera.
+   *
+   * @param camera Camera
+   */
+  void StartAutomaticCapture(const cs::VideoSource& camera);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * <p>This overload calls {@link #AddAxisCamera(String, String)} with
+   * name "Axis Camera".
+   *
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  cs::AxisCamera AddAxisCamera(llvm::StringRef host);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * <p>This overload calls {@link #AddAxisCamera(String, String)} with
+   * name "Axis Camera".
+   *
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  cs::AxisCamera AddAxisCamera(const char* host);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * <p>This overload calls {@link #AddAxisCamera(String, String)} with
+   * name "Axis Camera".
+   *
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  cs::AxisCamera AddAxisCamera(const std::string& host);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * <p>This overload calls {@link #AddAxisCamera(String, String[])} with
+   * name "Axis Camera".
+   *
+   * @param hosts Array of Camera host IPs/DNS names
+   */
+  cs::AxisCamera AddAxisCamera(llvm::ArrayRef<std::string> hosts);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * <p>This overload calls {@link #AddAxisCamera(String, String[])} with
+   * name "Axis Camera".
+   *
+   * @param hosts Array of Camera host IPs/DNS names
+   */
+  template <typename T>
+  cs::AxisCamera AddAxisCamera(std::initializer_list<T> hosts);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * @param name The name to give the camera
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  cs::AxisCamera AddAxisCamera(llvm::StringRef name, llvm::StringRef host);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * @param name The name to give the camera
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  cs::AxisCamera AddAxisCamera(llvm::StringRef name, const char* host);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * @param name The name to give the camera
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  cs::AxisCamera AddAxisCamera(llvm::StringRef name, const std::string& host);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * @param name The name to give the camera
+   * @param hosts Array of Camera host IPs/DNS names
+   */
+  cs::AxisCamera AddAxisCamera(llvm::StringRef name,
+                               llvm::ArrayRef<std::string> hosts);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * @param name The name to give the camera
+   * @param hosts Array of Camera host IPs/DNS names
+   */
+  template <typename T>
+  cs::AxisCamera AddAxisCamera(llvm::StringRef name,
+                               std::initializer_list<T> hosts);
+
+  /**
+   * Get OpenCV access to the primary camera feed.  This allows you to
+   * get images from the camera for image processing on the roboRIO.
+   *
+   * <p>This is only valid to call after a camera feed has been added
+   * with startAutomaticCapture() or addServer().
+   */
+  cs::CvSink GetVideo();
+
+  /**
+   * Get OpenCV access to the specified camera.  This allows you to get
+   * images from the camera for image processing on the roboRIO.
+   *
+   * @param camera Camera (e.g. as returned by startAutomaticCapture).
+   */
+  cs::CvSink GetVideo(const cs::VideoSource& camera);
+
+  /**
+   * Get OpenCV access to the specified camera.  This allows you to get
+   * images from the camera for image processing on the roboRIO.
+   *
+   * @param name Camera name
+   */
+  cs::CvSink GetVideo(llvm::StringRef name);
+
+  /**
+   * Create a MJPEG stream with OpenCV input. This can be called to pass custom
+   * annotated images to the dashboard.
+   *
+   * @param name Name to give the stream
+   * @param width Width of the image being sent
+   * @param height Height of the image being sent
+   */
+  cs::CvSource PutVideo(llvm::StringRef name, int width, int height);
+
+  /**
+   * Adds a MJPEG server at the next available port.
+   *
+   * @param name Server name
+   */
+  cs::MjpegServer AddServer(llvm::StringRef name);
+
+  /**
+   * Adds a MJPEG server.
+   *
+   * @param name Server name
+   */
+  cs::MjpegServer AddServer(llvm::StringRef name, int port);
+
+  /**
+   * Adds an already created server.
+   *
+   * @param server Server
+   */
+  void AddServer(const cs::VideoSink& server);
+
+  /**
+   * Removes a server by name.
+   *
+   * @param name Server name
+   */
+  void RemoveServer(llvm::StringRef name);
+
+  /**
+   * Get server for the primary camera feed.
+   *
+   * <p>This is only valid to call after a camera feed has been added
+   * with StartAutomaticCapture() or AddServer().
+   */
+  cs::VideoSink GetServer();
+
+  /**
+   * Gets a server by name.
+   *
+   * @param name Server name
+   */
+  cs::VideoSink GetServer(llvm::StringRef name);
+
+  /**
+   * Adds an already created camera.
+   *
+   * @param camera Camera
+   */
+  void AddCamera(const cs::VideoSource& camera);
+
+  /**
+   * Removes a camera by name.
+   *
+   * @param name Camera name
+   */
+  void RemoveCamera(llvm::StringRef name);
+
+  /**
+   * Sets the size of the image to use. Use the public kSize constants to set
+   * the correct mode, or set it directly on a camera and call the appropriate
+   * StartAutomaticCapture method.
+   *
+   * @deprecated Use SetResolution on the UsbCamera returned by
+   *     StartAutomaticCapture() instead.
+   * @param size The size to use
+   */
+  void SetSize(int size);
+
+ private:
+  CameraServer();
+
+  std::shared_ptr<ITable> GetSourceTable(CS_Source source);
+  std::vector<std::string> GetSinkStreamValues(CS_Sink sink);
+  std::vector<std::string> GetSourceStreamValues(CS_Source source);
+  void UpdateStreamValues();
+
+  static constexpr char const* kPublishName = "/CameraPublisher";
+
+  std::mutex m_mutex;
+  std::atomic<int> m_defaultUsbDevice;
+  std::string m_primarySourceName;
+  llvm::StringMap<cs::VideoSource> m_sources;
+  llvm::StringMap<cs::VideoSink> m_sinks;
+  llvm::DenseMap<CS_Source, std::shared_ptr<ITable>> m_tables;
+  std::shared_ptr<NetworkTable> m_publishTable;
+  cs::VideoListener m_videoListener;
+  int m_tableListener;
+  int m_nextPort;
+  std::vector<std::string> m_addresses;
+};
+
+}  // namespace frc
+
+#include "CameraServer.inc"
diff --git a/wpilibc/athena/include/CameraServer.inc b/wpilibc/athena/include/CameraServer.inc
new file mode 100644
index 0000000..66050c2
--- /dev/null
+++ b/wpilibc/athena/include/CameraServer.inc
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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 <string>
+#include <vector>
+
+namespace frc {
+
+template <typename T>
+inline cs::AxisCamera CameraServer::AddAxisCamera(
+    std::initializer_list<T> hosts) {
+  return AddAxisCamera("Axis Camera", hosts);
+}
+
+template <typename T>
+inline cs::AxisCamera CameraServer::AddAxisCamera(
+    llvm::StringRef name, std::initializer_list<T> hosts) {
+  std::vector<std::string> vec;
+  vec.reserve(hosts.size());
+  for (const auto& host : hosts) vec.emplace_back(host);
+  return AddAxisCamera(name, vec);
+}
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/Compressor.h b/wpilibc/athena/include/Compressor.h
new file mode 100644
index 0000000..7bb7e8d
--- /dev/null
+++ b/wpilibc/athena/include/Compressor.h
@@ -0,0 +1,69 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "LiveWindow/LiveWindowSendable.h"
+#include "SensorBase.h"
+#include "tables/ITableListener.h"
+
+namespace frc {
+
+/**
+ * PCM compressor
+ */
+class Compressor : public SensorBase,
+                   public LiveWindowSendable,
+                   public ITableListener {
+ 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();
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew) override;
+
+ protected:
+  HAL_CompressorHandle m_compressorHandle;
+
+ private:
+  void SetCompressor(bool on);
+  int m_module;
+
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/ControllerPower.h b/wpilibc/athena/include/ControllerPower.h
new file mode 100644
index 0000000..f6b4720
--- /dev/null
+++ b/wpilibc/athena/include/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/wpilibc/athena/include/Counter.h b/wpilibc/athena/include/Counter.h
new file mode 100644
index 0000000..643f2b2
--- /dev/null
+++ b/wpilibc/athena/include/Counter.h
@@ -0,0 +1,119 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "AnalogTrigger.h"
+#include "CounterBase.h"
+#include "HAL/Counter.h"
+#include "HAL/Types.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "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 SensorBase,
+                public CounterBase,
+                public LiveWindowSendable {
+ 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);
+  WPI_DEPRECATED("Use pass-by-reference instead.")
+  explicit Counter(AnalogTrigger* trigger);
+  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; }
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+ protected:
+  // Makes the counter count up.
+  std::shared_ptr<DigitalSource> m_upSource;
+  // Makes the counter count down.
+  std::shared_ptr<DigitalSource> m_downSource;
+  // The FPGA counter object
+  HAL_CounterHandle m_counter = HAL_kInvalidHandle;
+
+ private:
+  int m_index = 0;  ///< The index of this counter.
+
+  std::shared_ptr<ITable> m_table;
+  friend class DigitalGlitchFilter;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/CounterBase.h b/wpilibc/athena/include/CounterBase.h
new file mode 100644
index 0000000..868dbe6
--- /dev/null
+++ b/wpilibc/athena/include/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/wpilibc/athena/include/DigitalGlitchFilter.h b/wpilibc/athena/include/DigitalGlitchFilter.h
new file mode 100644
index 0000000..f5c882c
--- /dev/null
+++ b/wpilibc/athena/include/DigitalGlitchFilter.h
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "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 SensorBase {
+ 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 priority_mutex m_mutex;
+  static ::std::array<bool, 3> m_filterAllocated;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/DigitalInput.h b/wpilibc/athena/include/DigitalInput.h
new file mode 100644
index 0000000..92a762f
--- /dev/null
+++ b/wpilibc/athena/include/DigitalInput.h
@@ -0,0 +1,57 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DigitalSource.h"
+#include "LiveWindow/LiveWindowSendable.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 LiveWindowSendable {
+ 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;
+
+  void UpdateTable();
+  void StartLiveWindowMode();
+  void StopLiveWindowMode();
+  std::string GetSmartDashboardType() const;
+  void InitTable(std::shared_ptr<ITable> subTable);
+  std::shared_ptr<ITable> GetTable() const;
+
+ private:
+  int m_channel;
+  HAL_DigitalHandle m_handle;
+
+  std::shared_ptr<ITable> m_table;
+  friend class DigitalGlitchFilter;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/DigitalOutput.h b/wpilibc/athena/include/DigitalOutput.h
new file mode 100644
index 0000000..8431191
--- /dev/null
+++ b/wpilibc/athena/include/DigitalOutput.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 "DigitalSource.h"
+#include "HAL/Types.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "tables/ITableListener.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 ITableListener,
+                      public LiveWindowSendable {
+ 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;
+
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew) override;
+  void UpdateTable();
+  void StartLiveWindowMode();
+  void StopLiveWindowMode();
+  std::string GetSmartDashboardType() const;
+  void InitTable(std::shared_ptr<ITable> subTable);
+  std::shared_ptr<ITable> GetTable() const;
+
+ private:
+  int m_channel;
+  HAL_DigitalHandle m_handle;
+  HAL_DigitalPWMHandle m_pwmGenerator;
+
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/DigitalSource.h b/wpilibc/athena/include/DigitalSource.h
new file mode 100644
index 0000000..d3d6523
--- /dev/null
+++ b/wpilibc/athena/include/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 "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/wpilibc/athena/include/DoubleSolenoid.h b/wpilibc/athena/include/DoubleSolenoid.h
new file mode 100644
index 0000000..0a25870
--- /dev/null
+++ b/wpilibc/athena/include/DoubleSolenoid.h
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "LiveWindow/LiveWindowSendable.h"
+#include "SolenoidBase.h"
+#include "tables/ITableListener.h"
+
+namespace frc {
+
+/**
+ * DoubleSolenoid class for running 2 channels of high voltage Digital Output
+ * (PCM).
+ *
+ * The DoubleSolenoid class is typically used for pneumatics solenoids that
+ * have two positions controlled by two separate channels.
+ */
+class DoubleSolenoid : public SolenoidBase,
+                       public LiveWindowSendable,
+                       public ITableListener {
+ public:
+  enum Value { kOff, kForward, kReverse };
+
+  explicit DoubleSolenoid(int forwardChannel, int reverseChannel);
+  DoubleSolenoid(int moduleNumber, int forwardChannel, int reverseChannel);
+  virtual ~DoubleSolenoid();
+  virtual void Set(Value value);
+  virtual Value Get() const;
+  bool IsFwdSolenoidBlackListed() const;
+  bool IsRevSolenoidBlackListed() const;
+
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew);
+  void UpdateTable();
+  void StartLiveWindowMode();
+  void StopLiveWindowMode();
+  std::string GetSmartDashboardType() const;
+  void InitTable(std::shared_ptr<ITable> subTable);
+  std::shared_ptr<ITable> GetTable() const;
+
+ private:
+  int m_forwardChannel;  ///< The forward channel on the module to control.
+  int m_reverseChannel;  ///< The reverse channel on the module to control.
+  int m_forwardMask;     ///< The mask for the forward channel.
+  int m_reverseMask;     ///< The mask for the reverse channel.
+  HAL_SolenoidHandle m_forwardHandle = HAL_kInvalidHandle;
+  HAL_SolenoidHandle m_reverseHandle = HAL_kInvalidHandle;
+
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/DriverStation.h b/wpilibc/athena/include/DriverStation.h
new file mode 100644
index 0000000..6bd2ea6
--- /dev/null
+++ b/wpilibc/athena/include/DriverStation.h
@@ -0,0 +1,143 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "HAL/cpp/priority_condition_variable.h"
+#include "HAL/cpp/priority_mutex.h"
+#include "RobotState.h"
+#include "SensorBase.h"
+#include "llvm/StringRef.h"
+
+namespace frc {
+
+/**
+ * Provide access to the network communication data to / from the Driver
+ * Station.
+ */
+class DriverStation : public SensorBase, public RobotStateInterface {
+ 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 override;
+  bool IsDisabled() const override;
+  bool IsAutonomous() const override;
+  bool IsOperatorControl() const override;
+  bool IsTest() const override;
+  bool IsDSAttached() const;
+  bool IsNewControlData() const;
+  bool IsFMSAttached() const;
+  bool IsSysActive() const;
+  bool IsBrownedOut() const;
+
+  Alliance GetAlliance() const;
+  int GetLocation() const;
+  void WaitForData();
+  bool WaitForData(double timeout);
+  double GetMatchTime() const;
+  double GetBatteryVoltage() const;
+
+  /** Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only
+   * @param entering If true, starting disabled code; if false, leaving disabled
+   * code */
+  void InDisabled(bool entering) { m_userInDisabled = entering; }
+  /** Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only
+   * @param entering If true, starting autonomous code; if false, leaving
+   * autonomous code */
+  void InAutonomous(bool entering) { m_userInAutonomous = entering; }
+  /** Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only
+   * @param entering If true, starting teleop code; if false, leaving teleop
+   * code */
+  void InOperatorControl(bool entering) { m_userInTeleop = entering; }
+  /** Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only
+   * @param entering If true, starting test code; if false, leaving test code */
+  void InTest(bool entering) { m_userInTest = entering; }
+
+ protected:
+  void GetData();
+
+ private:
+  DriverStation();
+  void ReportJoystickUnpluggedError(llvm::StringRef message);
+  void ReportJoystickUnpluggedWarning(llvm::StringRef message);
+  void Run();
+  void UpdateControlWord(bool force, HAL_ControlWord& controlWord) const;
+
+  // 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;
+
+  // Internal Driver Station thread
+  std::thread m_dsThread;
+  std::atomic<bool> m_isRunning{false};
+
+  // WPILib WaitForData control variables
+  bool m_waitForDataPredicate = false;
+  std::condition_variable_any m_waitForDataCond;
+  priority_mutex m_waitForDataMutex;
+
+  mutable std::atomic<bool> m_newControlData{false};
+
+  mutable priority_mutex m_joystickDataMutex;
+
+  // Robot state status variables
+  bool m_userInDisabled = false;
+  bool m_userInAutonomous = false;
+  bool m_userInTeleop = false;
+  bool m_userInTest = false;
+
+  // Control word variables
+  mutable HAL_ControlWord m_controlWordCache;
+  mutable std::chrono::steady_clock::time_point m_lastControlWordUpdate;
+  mutable priority_mutex m_controlWordMutex;
+
+  double m_nextMessageTime = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/Encoder.h b/wpilibc/athena/include/Encoder.h
new file mode 100644
index 0000000..f429703
--- /dev/null
+++ b/wpilibc/athena/include/Encoder.h
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include "Counter.h"
+#include "CounterBase.h"
+#include "HAL/Encoder.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "PIDSource.h"
+#include "SensorBase.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 SensorBase,
+                public CounterBase,
+                public PIDSource,
+                public LiveWindowSendable {
+ public:
+  enum IndexingType {
+    kResetWhileHigh,
+    kResetWhileLow,
+    kResetOnFallingEdge,
+    kResetOnRisingEdge
+  };
+
+  Encoder(int aChannel, int bChannel, bool reverseDirection = false,
+          EncodingType encodingType = k4X);
+  Encoder(std::shared_ptr<DigitalSource> aSource,
+          std::shared_ptr<DigitalSource> bSource, bool reverseDirection = false,
+          EncodingType encodingType = k4X);
+  Encoder(DigitalSource* aSource, DigitalSource* bSource,
+          bool reverseDirection = false, EncodingType encodingType = k4X);
+  Encoder(DigitalSource& aSource, DigitalSource& bSource,
+          bool reverseDirection = false, EncodingType encodingType = k4X);
+  virtual ~Encoder();
+
+  // CounterBase interface
+  int Get() const override;
+  int GetRaw() const;
+  int GetEncodingScale() const;
+  void Reset() override;
+  double GetPeriod() const override;
+  void SetMaxPeriod(double maxPeriod) override;
+  bool GetStopped() const override;
+  bool GetDirection() const override;
+
+  double GetDistance() const;
+  double GetRate() const;
+  void SetMinRate(double minRate);
+  void SetDistancePerPulse(double distancePerPulse);
+  void SetReverseDirection(bool reverseDirection);
+  void SetSamplesToAverage(int samplesToAverage);
+  int GetSamplesToAverage() const;
+  double PIDGet() override;
+
+  void SetIndexSource(int channel, IndexingType type = kResetOnRisingEdge);
+  WPI_DEPRECATED("Use pass-by-reference instead.")
+  void SetIndexSource(DigitalSource* source,
+                      IndexingType type = kResetOnRisingEdge);
+  void SetIndexSource(const DigitalSource& source,
+                      IndexingType type = kResetOnRisingEdge);
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+  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;
+
+  std::shared_ptr<ITable> m_table;
+  friend class DigitalGlitchFilter;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/GearTooth.h b/wpilibc/athena/include/GearTooth.h
new file mode 100644
index 0000000..8236db4
--- /dev/null
+++ b/wpilibc/athena/include/GearTooth.h
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Counter.h"
+
+namespace frc {
+
+/**
+ * Alias for counter class.
+ * Implement the gear tooth sensor supplied by FIRST. Currently there is no
+ * reverse sensing on the gear tooth sensor, but in future versions we might
+ * implement the necessary timing in the FPGA to sense direction.
+ */
+class GearTooth : public Counter {
+ public:
+  /// 55 uSec for threshold
+  static constexpr double kGearToothThreshold = 55e-6;
+  explicit GearTooth(int channel, bool directionSensitive = false);
+  explicit GearTooth(DigitalSource* source, bool directionSensitive = false);
+  explicit GearTooth(std::shared_ptr<DigitalSource> source,
+                     bool directionSensitive = false);
+  virtual ~GearTooth() = default;
+  void EnableDirectionSensing(bool directionSensitive);
+
+  std::string GetSmartDashboardType() const override;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/I2C.h b/wpilibc/athena/include/I2C.h
new file mode 100644
index 0000000..78decc5
--- /dev/null
+++ b/wpilibc/athena/include/I2C.h
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SensorBase.h"
+
+namespace frc {
+
+/**
+ * I2C bus interface class.
+ *
+ * This class is intended to be used by sensor (and other I2C device) drivers.
+ * It probably should not be used directly.
+ *
+ */
+class I2C : SensorBase {
+ public:
+  enum Port { kOnboard, kMXP };
+
+  I2C(Port port, int deviceAddress);
+  virtual ~I2C();
+
+  I2C(const I2C&) = delete;
+  I2C& operator=(const I2C&) = delete;
+
+  bool Transaction(uint8_t* dataToSend, int sendSize, uint8_t* dataReceived,
+                   int receiveSize);
+  bool AddressOnly();
+  bool Write(int registerAddress, uint8_t data);
+  bool WriteBulk(uint8_t* data, int count);
+  bool Read(int registerAddress, int count, uint8_t* data);
+  bool ReadOnly(int count, uint8_t* buffer);
+  // void Broadcast(int registerAddress, uint8_t data);
+  bool VerifySensor(int registerAddress, int count, const uint8_t* expected);
+
+ private:
+  Port m_port;
+  int m_deviceAddress;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/Internal/HardwareHLReporting.h b/wpilibc/athena/include/Internal/HardwareHLReporting.h
new file mode 100644
index 0000000..d866192
--- /dev/null
+++ b/wpilibc/athena/include/Internal/HardwareHLReporting.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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 "HLUsageReporting.h"
+
+namespace frc {
+
+class HardwareHLReporting : public HLUsageReportingInterface {
+ public:
+  virtual void ReportScheduler();
+  virtual void ReportSmartDashboard();
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/InterruptableSensorBase.h b/wpilibc/athena/include/InterruptableSensorBase.h
new file mode 100644
index 0000000..49d877f
--- /dev/null
+++ b/wpilibc/athena/include/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 "AnalogTriggerType.h"
+#include "HAL/Interrupts.h"
+#include "SensorBase.h"
+
+namespace frc {
+
+class InterruptableSensorBase : public SensorBase {
+ 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);                  ///< Asynchronus handler version.
+  virtual void RequestInterrupts();  ///< Synchronus Wait version.
+  virtual void
+  CancelInterrupts();  ///< Free up the underlying chipobject functions.
+  virtual WaitResult WaitForInterrupt(
+      double timeout,
+      bool ignorePrevious = true);  ///< Synchronus 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/wpilibc/athena/include/IterativeRobot.h b/wpilibc/athena/include/IterativeRobot.h
new file mode 100644
index 0000000..34847d6
--- /dev/null
+++ b/wpilibc/athena/include/IterativeRobot.h
@@ -0,0 +1,74 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "RobotBase.h"
+
+namespace frc {
+
+/**
+ * IterativeRobot implements a specific type of Robot Program framework,
+ * extending the RobotBase class.
+ *
+ * The IterativeRobot class is intended to be subclassed by a user creating a
+ * robot program.
+ *
+ * This class is intended to implement the "old style" default code, by
+ * providing the following functions which are called by the main loop,
+ * StartCompetition(), at the appropriate times:
+ *
+ * RobotInit() -- provide for initialization at robot power-on
+ *
+ * Init() functions -- each of the following functions is called once when the
+ *                     appropriate mode is entered:
+ *  - DisabledInit()   -- called only when first disabled
+ *  - AutonomousInit() -- called each and every time autonomous is entered from
+ *                        another mode
+ *  - TeleopInit()     -- called each and every time teleop is entered from
+ *                        another mode
+ *  - TestInit()       -- called each and every time test is entered from
+ *                        another mode
+ *
+ * Periodic() functions -- each of these functions is called each time a
+ *                         new packet is received from the driver station:
+ *   - RobotPeriodic()
+ *   - DisabledPeriodic()
+ *   - AutonomousPeriodic()
+ *   - TeleopPeriodic()
+ *   - TestPeriodic()
+ *
+ */
+
+class IterativeRobot : public RobotBase {
+ public:
+  virtual void StartCompetition();
+
+  virtual void RobotInit();
+  virtual void DisabledInit();
+  virtual void AutonomousInit();
+  virtual void TeleopInit();
+  virtual void TestInit();
+
+  virtual void RobotPeriodic();
+  virtual void DisabledPeriodic();
+  virtual void AutonomousPeriodic();
+  virtual void TeleopPeriodic();
+  virtual void TestPeriodic();
+
+ protected:
+  virtual ~IterativeRobot() = default;
+  IterativeRobot() = default;
+
+ private:
+  bool m_disabledInitialized = false;
+  bool m_autonomousInitialized = false;
+  bool m_teleopInitialized = false;
+  bool m_testInitialized = false;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/Jaguar.h b/wpilibc/athena/include/Jaguar.h
new file mode 100644
index 0000000..1c29fde
--- /dev/null
+++ b/wpilibc/athena/include/Jaguar.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 "PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Luminary Micro / Vex Robotics Jaguar Speed Controller with PWM control
+ */
+class Jaguar : public PWMSpeedController {
+ public:
+  explicit Jaguar(int channel);
+  virtual ~Jaguar() = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/MotorSafety.h b/wpilibc/athena/include/MotorSafety.h
new file mode 100644
index 0000000..27c938c
--- /dev/null
+++ b/wpilibc/athena/include/MotorSafety.h
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#define DEFAULT_SAFETY_EXPIRATION 0.1
+
+#include <sstream>
+
+namespace frc {
+
+class MotorSafety {
+ public:
+  virtual void SetExpiration(double timeout) = 0;
+  virtual double GetExpiration() const = 0;
+  virtual bool IsAlive() const = 0;
+  virtual void StopMotor() = 0;
+  virtual void SetSafetyEnabled(bool enabled) = 0;
+  virtual bool IsSafetyEnabled() const = 0;
+  virtual void GetDescription(std::ostringstream& desc) const = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/MotorSafetyHelper.h b/wpilibc/athena/include/MotorSafetyHelper.h
new file mode 100644
index 0000000..829a9db
--- /dev/null
+++ b/wpilibc/athena/include/MotorSafetyHelper.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 <set>
+
+#include "ErrorBase.h"
+#include "HAL/cpp/priority_mutex.h"
+
+namespace frc {
+
+class MotorSafety;
+
+class MotorSafetyHelper : public ErrorBase {
+ public:
+  explicit MotorSafetyHelper(MotorSafety* safeObject);
+  ~MotorSafetyHelper();
+  void Feed();
+  void SetExpiration(double expirationTime);
+  double GetExpiration() const;
+  bool IsAlive() const;
+  void Check();
+  void SetSafetyEnabled(bool enabled);
+  bool IsSafetyEnabled() const;
+  static void CheckMotors();
+
+ private:
+  // the expiration time for this object
+  double m_expiration;
+  // true if motor safety is enabled for this motor
+  bool m_enabled;
+  // the FPGA clock value when this motor has expired
+  double m_stopTime;
+  // protect accesses to the state for this object
+  mutable priority_recursive_mutex m_syncMutex;
+  // the object that is using the helper
+  MotorSafety* m_safeObject;
+  // List of all existing MotorSafetyHelper objects.
+  static std::set<MotorSafetyHelper*> m_helperList;
+  // protect accesses to the list of helpers
+  static priority_recursive_mutex m_listMutex;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/Notifier.h b/wpilibc/athena/include/Notifier.h
new file mode 100644
index 0000000..0ea50ff
--- /dev/null
+++ b/wpilibc/athena/include/Notifier.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 <atomic>
+#include <functional>
+#include <utility>
+
+#include "ErrorBase.h"
+#include "HAL/Notifier.h"
+#include "HAL/cpp/priority_mutex.h"
+
+namespace frc {
+
+typedef std::function<void()> TimerEventHandler;
+
+class Notifier : public ErrorBase {
+ public:
+  explicit Notifier(TimerEventHandler handler);
+
+  template <typename Callable, typename Arg, typename... Args>
+  Notifier(Callable&& f, Arg&& arg, Args&&... args)
+      : Notifier(std::bind(std::forward<Callable>(f), std::forward<Arg>(arg),
+                           std::forward<Args>(args)...)) {}
+
+  virtual ~Notifier();
+
+  Notifier(const Notifier&) = delete;
+  Notifier& operator=(const Notifier&) = delete;
+
+  void StartSingle(double delay);
+  void StartPeriodic(double period);
+  void Stop();
+
+ private:
+  // update the HAL alarm
+  void UpdateAlarm();
+  // HAL callback
+  static void Notify(uint64_t currentTimeInt, HAL_NotifierHandle handle);
+
+  // used to constrain execution between destructors and callback
+  static priority_mutex m_destructorMutex;
+  // held while updating process information
+  priority_mutex m_processMutex;
+  // HAL handle, atomic for proper destruction
+  std::atomic<HAL_NotifierHandle> m_notifier{0};
+  // address of the handler
+  TimerEventHandler m_handler;
+  // the absolute expiration time
+  double m_expirationTime = 0;
+  // the relative time (either periodic or single)
+  double m_period = 0;
+  // true if this is a periodic event
+  bool m_periodic = false;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/PWM.h b/wpilibc/athena/include/PWM.h
new file mode 100644
index 0000000..e66a81e
--- /dev/null
+++ b/wpilibc/athena/include/PWM.h
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "LiveWindow/LiveWindowSendable.h"
+#include "SensorBase.h"
+#include "tables/ITableListener.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 SensorBase,
+            public ITableListener,
+            public LiveWindowSendable {
+ 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:
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew) override;
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+  std::shared_ptr<ITable> m_table;
+
+ private:
+  int m_channel;
+  HAL_DigitalHandle m_handle;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/PWMSpeedController.h b/wpilibc/athena/include/PWMSpeedController.h
new file mode 100644
index 0000000..9060413
--- /dev/null
+++ b/wpilibc/athena/include/PWMSpeedController.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SafePWM.h"
+#include "SpeedController.h"
+
+namespace frc {
+
+/**
+ * Common base class for all PWM Speed Controllers
+ */
+class PWMSpeedController : public SafePWM, public SpeedController {
+ public:
+  virtual ~PWMSpeedController() = default;
+  void Set(double value) override;
+  double Get() const override;
+  void Disable() override;
+  void StopMotor() override;
+
+  void PIDWrite(double output) override;
+
+  void SetInverted(bool isInverted) override;
+  bool GetInverted() const override;
+
+ protected:
+  explicit PWMSpeedController(int channel);
+
+ private:
+  bool m_isInverted = false;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/PowerDistributionPanel.h b/wpilibc/athena/include/PowerDistributionPanel.h
new file mode 100644
index 0000000..f7d643f
--- /dev/null
+++ b/wpilibc/athena/include/PowerDistributionPanel.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "LiveWindow/LiveWindowSendable.h"
+#include "SensorBase.h"
+
+namespace frc {
+
+/**
+ * Class for getting voltage, current, temperature, power and energy from the
+ * CAN PDP.
+ */
+class PowerDistributionPanel : public SensorBase, public LiveWindowSendable {
+ 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();
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+ private:
+  std::shared_ptr<ITable> m_table;
+  int m_module;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/Preferences.h b/wpilibc/athena/include/Preferences.h
new file mode 100644
index 0000000..1dcd39b
--- /dev/null
+++ b/wpilibc/athena/include/Preferences.h
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* 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
+
+#include <map>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include "ErrorBase.h"
+#include "networktables/NetworkTable.h"
+#include "tables/ITableListener.h"
+
+namespace frc {
+
+/**
+ * The preferences class provides a relatively simple way to save important
+ * values to the roboRIO to access the next time the roboRIO is booted.
+ *
+ * <p>This class loads and saves from a file inside the roboRIO.  The user can
+ * not access the file directly, but may modify values at specific fields which
+ * will then be automatically periodically saved to the file by the NetworkTable
+ * server.</p>
+ *
+ * <p>This class is thread safe.</p>
+ *
+ * <p>This will also interact with {@link NetworkTable} by creating a table
+ * called "Preferences" with all the key-value pairs.</p>
+ */
+class Preferences : public ErrorBase {
+ public:
+  static Preferences* GetInstance();
+
+  std::vector<std::string> GetKeys();
+  std::string GetString(llvm::StringRef key, llvm::StringRef defaultValue = "");
+  int GetInt(llvm::StringRef key, int defaultValue = 0);
+  double GetDouble(llvm::StringRef key, double defaultValue = 0.0);
+  float GetFloat(llvm::StringRef key, float defaultValue = 0.0);
+  bool GetBoolean(llvm::StringRef key, bool defaultValue = false);
+  int64_t GetLong(llvm::StringRef key, int64_t defaultValue = 0);
+  void PutString(llvm::StringRef key, llvm::StringRef value);
+  void PutInt(llvm::StringRef key, int value);
+  void PutDouble(llvm::StringRef key, double value);
+  void PutFloat(llvm::StringRef key, float value);
+  void PutBoolean(llvm::StringRef key, bool value);
+  void PutLong(llvm::StringRef key, int64_t value);
+  WPI_DEPRECATED(
+      "Saving is now automatically performed by the NetworkTables server.")
+  void Save();
+  bool ContainsKey(llvm::StringRef key);
+  void Remove(llvm::StringRef key);
+
+ protected:
+  Preferences();
+  virtual ~Preferences() = default;
+
+ private:
+  std::shared_ptr<ITable> m_table;
+  class Listener : public ITableListener {
+   public:
+    void ValueChanged(ITable* source, llvm::StringRef key,
+                      std::shared_ptr<nt::Value> value, bool isNew) override;
+    void ValueChangedEx(ITable* source, llvm::StringRef key,
+                        std::shared_ptr<nt::Value> value,
+                        uint32_t flags) override;
+  };
+  Listener m_listener;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/Relay.h b/wpilibc/athena/include/Relay.h
new file mode 100644
index 0000000..eac3967
--- /dev/null
+++ b/wpilibc/athena/include/Relay.h
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "LiveWindow/LiveWindowSendable.h"
+#include "MotorSafety.h"
+#include "SensorBase.h"
+#include "tables/ITable.h"
+#include "tables/ITableListener.h"
+
+namespace frc {
+
+class MotorSafetyHelper;
+
+/**
+ * Class for Spike style relay outputs.
+ * Relays are intended to be connected to spikes or similar relays. The relay
+ * channels controls a pair of pins that are either both off, one on, the other
+ * on, or both on. This translates into two spike outputs at 0v, one at 12v and
+ * one at 0v, one at 0v and the other at 12v, or two spike outputs at 12V. This
+ * allows off, full forward, or full reverse control of motors without variable
+ * speed.  It also allows the two channels (forward and reverse) to be used
+ * independently for something that does not care about voltage polarity (like
+ * a solenoid).
+ */
+class Relay : public MotorSafety,
+              public SensorBase,
+              public ITableListener,
+              public LiveWindowSendable {
+ 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;
+
+  void SetExpiration(double timeout) override;
+  double GetExpiration() const override;
+  bool IsAlive() const override;
+  void StopMotor() override;
+  bool IsSafetyEnabled() const override;
+  void SetSafetyEnabled(bool enabled) override;
+  void GetDescription(std::ostringstream& desc) const override;
+
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew) override;
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+  std::shared_ptr<ITable> m_table;
+
+ private:
+  int m_channel;
+  Direction m_direction;
+
+  HAL_RelayHandle m_forwardHandle = HAL_kInvalidHandle;
+  HAL_RelayHandle m_reverseHandle = HAL_kInvalidHandle;
+
+  std::unique_ptr<MotorSafetyHelper> m_safetyHelper;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/RobotBase.h b/wpilibc/athena/include/RobotBase.h
new file mode 100644
index 0000000..26a0c91
--- /dev/null
+++ b/wpilibc/athena/include/RobotBase.h
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Base.h"
+#include "HAL/HAL.h"
+
+namespace frc {
+
+class DriverStation;
+
+#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();                                                \
+  }
+
+/**
+ * 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:
+  bool IsEnabled() const;
+  bool IsDisabled() const;
+  bool IsAutonomous() const;
+  bool IsOperatorControl() const;
+  bool IsTest() const;
+  bool IsNewDataAvailable() const;
+  static std::thread::id GetThreadId();
+  virtual void StartCompetition() = 0;
+
+ protected:
+  RobotBase();
+  virtual ~RobotBase() = default;
+
+  RobotBase(const RobotBase&) = delete;
+  RobotBase& operator=(const RobotBase&) = delete;
+
+  DriverStation& m_ds;
+
+  static std::thread::id m_threadId;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/RobotDrive.h b/wpilibc/athena/include/RobotDrive.h
new file mode 100644
index 0000000..8e23e62
--- /dev/null
+++ b/wpilibc/athena/include/RobotDrive.h
@@ -0,0 +1,125 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <sstream>
+
+#include "ErrorBase.h"
+#include "MotorSafety.h"
+#include "MotorSafetyHelper.h"
+
+namespace frc {
+
+class SpeedController;
+class GenericHID;
+
+/**
+ * Utility class for handling Robot drive based on a definition of the motor
+ * configuration.
+ * The robot drive class handles basic driving for a robot. Currently, 2 and 4
+ * motor tank and mecanum drive trains are supported. In the future other drive
+ * types like swerve might be implemented. Motor channel numbers are passed
+ * supplied on creation of the class. Those are used for either the Drive
+ * function (intended for hand created drive code, such as autonomous) or with
+ * the Tank/Arcade functions intended to be used for Operator Control driving.
+ */
+class RobotDrive : public MotorSafety, public ErrorBase {
+ public:
+  enum MotorType {
+    kFrontLeftMotor = 0,
+    kFrontRightMotor = 1,
+    kRearLeftMotor = 2,
+    kRearRightMotor = 3
+  };
+
+  RobotDrive(int leftMotorChannel, int rightMotorChannel);
+  RobotDrive(int frontLeftMotorChannel, int rearLeftMotorChannel,
+             int frontRightMotorChannel, int rearRightMotorChannel);
+  RobotDrive(SpeedController* leftMotor, SpeedController* rightMotor);
+  RobotDrive(SpeedController& leftMotor, SpeedController& rightMotor);
+  RobotDrive(std::shared_ptr<SpeedController> leftMotor,
+             std::shared_ptr<SpeedController> rightMotor);
+  RobotDrive(SpeedController* frontLeftMotor, SpeedController* rearLeftMotor,
+             SpeedController* frontRightMotor, SpeedController* rearRightMotor);
+  RobotDrive(SpeedController& frontLeftMotor, SpeedController& rearLeftMotor,
+             SpeedController& frontRightMotor, SpeedController& rearRightMotor);
+  RobotDrive(std::shared_ptr<SpeedController> frontLeftMotor,
+             std::shared_ptr<SpeedController> rearLeftMotor,
+             std::shared_ptr<SpeedController> frontRightMotor,
+             std::shared_ptr<SpeedController> rearRightMotor);
+  virtual ~RobotDrive() = default;
+
+  RobotDrive(const RobotDrive&) = delete;
+  RobotDrive& operator=(const RobotDrive&) = delete;
+
+  void Drive(double outputMagnitude, double curve);
+  void TankDrive(GenericHID* leftStick, GenericHID* rightStick,
+                 bool squaredInputs = true);
+  void TankDrive(GenericHID& leftStick, GenericHID& rightStick,
+                 bool squaredInputs = true);
+  void TankDrive(GenericHID* leftStick, int leftAxis, GenericHID* rightStick,
+                 int rightAxis, bool squaredInputs = true);
+  void TankDrive(GenericHID& leftStick, int leftAxis, GenericHID& rightStick,
+                 int rightAxis, bool squaredInputs = true);
+  void TankDrive(double leftValue, double rightValue,
+                 bool squaredInputs = true);
+  void ArcadeDrive(GenericHID* stick, bool squaredInputs = true);
+  void ArcadeDrive(GenericHID& stick, bool squaredInputs = true);
+  void ArcadeDrive(GenericHID* moveStick, int moveChannel,
+                   GenericHID* rotateStick, int rotateChannel,
+                   bool squaredInputs = true);
+  void ArcadeDrive(GenericHID& moveStick, int moveChannel,
+                   GenericHID& rotateStick, int rotateChannel,
+                   bool squaredInputs = true);
+  void ArcadeDrive(double moveValue, double rotateValue,
+                   bool squaredInputs = true);
+  void MecanumDrive_Cartesian(double x, double y, double rotation,
+                              double gyroAngle = 0.0);
+  void MecanumDrive_Polar(double magnitude, double direction, double rotation);
+  void HolonomicDrive(double magnitude, double direction, double rotation);
+  virtual void SetLeftRightMotorOutputs(double leftOutput, double rightOutput);
+  void SetInvertedMotor(MotorType motor, bool isInverted);
+  void SetSensitivity(double sensitivity);
+  void SetMaxOutput(double maxOutput);
+
+  void SetExpiration(double timeout) override;
+  double GetExpiration() const override;
+  bool IsAlive() const override;
+  void StopMotor() override;
+  bool IsSafetyEnabled() const override;
+  void SetSafetyEnabled(bool enabled) override;
+  void GetDescription(std::ostringstream& desc) const override;
+
+ protected:
+  void InitRobotDrive();
+  double Limit(double num);
+  void Normalize(double* wheelSpeeds);
+  void RotateVector(double& x, double& y, double angle);
+
+  static const int kMaxNumberOfMotors = 4;
+  double m_sensitivity = 0.5;
+  double m_maxOutput = 1.0;
+  std::shared_ptr<SpeedController> m_frontLeftMotor;
+  std::shared_ptr<SpeedController> m_frontRightMotor;
+  std::shared_ptr<SpeedController> m_rearLeftMotor;
+  std::shared_ptr<SpeedController> m_rearRightMotor;
+  std::unique_ptr<MotorSafetyHelper> m_safetyHelper;
+
+ private:
+  int GetNumMotors() {
+    int motors = 0;
+    if (m_frontLeftMotor) motors++;
+    if (m_frontRightMotor) motors++;
+    if (m_rearLeftMotor) motors++;
+    if (m_rearRightMotor) motors++;
+    return motors;
+  }
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/SD540.h b/wpilibc/athena/include/SD540.h
new file mode 100644
index 0000000..65c49a8
--- /dev/null
+++ b/wpilibc/athena/include/SD540.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 "PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Mindsensors SD540 Speed Controller
+ */
+class SD540 : public PWMSpeedController {
+ public:
+  explicit SD540(int channel);
+  virtual ~SD540() = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/SPI.h b/wpilibc/athena/include/SPI.h
new file mode 100644
index 0000000..6a69e61
--- /dev/null
+++ b/wpilibc/athena/include/SPI.h
@@ -0,0 +1,74 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SensorBase.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 SensorBase {
+ public:
+  enum Port { kOnboardCS0, 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);
+
+  void InitAccumulator(double period, int cmd, int xfer_size, int valid_mask,
+                       int valid_value, int data_shift, int data_size,
+                       bool is_signed, bool big_endian);
+  void FreeAccumulator();
+  void ResetAccumulator();
+  void SetAccumulatorCenter(int center);
+  void SetAccumulatorDeadband(int deadband);
+  int GetAccumulatorLastValue() const;
+  int64_t GetAccumulatorValue() const;
+  int64_t GetAccumulatorCount() const;
+  double GetAccumulatorAverage() const;
+  void GetAccumulatorOutput(int64_t& value, int64_t& count) const;
+
+ protected:
+  int m_port;
+  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/wpilibc/athena/include/SafePWM.h b/wpilibc/athena/include/SafePWM.h
new file mode 100644
index 0000000..16a64c1
--- /dev/null
+++ b/wpilibc/athena/include/SafePWM.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 <sstream>
+
+#include "MotorSafety.h"
+#include "MotorSafetyHelper.h"
+#include "PWM.h"
+
+namespace frc {
+
+/**
+ * A safe version of the PWM class.
+ * It is safe because it implements the MotorSafety interface that provides
+ * timeouts in the event that the motor value is not updated before the
+ * expiration time. This delegates the actual work to a MotorSafetyHelper
+ * object that is used for all objects that implement MotorSafety.
+ */
+class SafePWM : public PWM, public MotorSafety {
+ public:
+  explicit SafePWM(int channel);
+  virtual ~SafePWM() = default;
+
+  void SetExpiration(double timeout);
+  double GetExpiration() const;
+  bool IsAlive() const;
+  void StopMotor();
+  bool IsSafetyEnabled() const;
+  void SetSafetyEnabled(bool enabled);
+  void GetDescription(std::ostringstream& desc) const;
+
+  virtual void SetSpeed(double speed);
+
+ private:
+  std::unique_ptr<MotorSafetyHelper> m_safetyHelper;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/SampleRobot.h b/wpilibc/athena/include/SampleRobot.h
new file mode 100644
index 0000000..09051e5
--- /dev/null
+++ b/wpilibc/athena/include/SampleRobot.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "RobotBase.h"
+
+namespace frc {
+
+class SampleRobot : public RobotBase {
+ public:
+  SampleRobot();
+  virtual ~SampleRobot() = default;
+  virtual void RobotInit();
+  virtual void Disabled();
+  virtual void Autonomous();
+  virtual void OperatorControl();
+  virtual void Test();
+  virtual void RobotMain();
+  void StartCompetition();
+
+ private:
+  bool m_robotMainOverridden;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/SensorBase.h b/wpilibc/athena/include/SensorBase.h
new file mode 100644
index 0000000..09720fc
--- /dev/null
+++ b/wpilibc/athena/include/SensorBase.h
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Base.h"
+#include "ErrorBase.h"
+
+namespace frc {
+
+/**
+ * Base class for all sensors.
+ * Stores most recent status information as well as containing utility functions
+ * for checking channels and error processing.
+ */
+class SensorBase : public ErrorBase {
+ public:
+  SensorBase() = default;
+  virtual ~SensorBase() = default;
+
+  SensorBase(const SensorBase&) = delete;
+  SensorBase& operator=(const SensorBase&) = delete;
+
+  static int GetDefaultSolenoidModule() { return 0; }
+
+  static bool CheckSolenoidModule(int moduleNumber);
+  static bool CheckDigitalChannel(int channel);
+  static bool CheckRelayChannel(int channel);
+  static bool CheckPWMChannel(int channel);
+  static bool CheckAnalogInputChannel(int channel);
+  static bool CheckAnalogOutputChannel(int channel);
+  static bool CheckSolenoidChannel(int channel);
+  static bool CheckPDPChannel(int channel);
+
+  static const int kDigitalChannels;
+  static const int kAnalogInputs;
+  static const int kAnalogOutputs;
+  static const int kSolenoidChannels;
+  static const int kSolenoidModules;
+  static const int kPwmChannels;
+  static const int kRelayChannels;
+  static const int kPDPChannels;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/SerialPort.h b/wpilibc/athena/include/SerialPort.h
new file mode 100644
index 0000000..7590b4f
--- /dev/null
+++ b/wpilibc/athena/include/SerialPort.h
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <string>
+
+#include "ErrorBase.h"
+#include "llvm/StringRef.h"
+#include "support/deprecated.h"
+
+namespace frc {
+
+/**
+ * Driver for the RS-232 serial port on the roboRIO.
+ *
+ * The current implementation uses the VISA formatted I/O mode.  This means that
+ * all traffic goes through the fomatted buffers.  This allows the intermingled
+ * use of Printf(), Scanf(), and the raw buffer accessors Read() and Write().
+ *
+ * More information can be found in the NI-VISA User Manual here:
+ *   http://www.ni.com/pdf/manuals/370423a.pdf
+ * and the NI-VISA Programmer's Reference Manual here:
+ *   http://www.ni.com/pdf/manuals/370132c.pdf
+ */
+class SerialPort : public ErrorBase {
+ public:
+  enum Parity {
+    kParity_None = 0,
+    kParity_Odd = 1,
+    kParity_Even = 2,
+    kParity_Mark = 3,
+    kParity_Space = 4
+  };
+  enum StopBits {
+    kStopBits_One = 10,
+    kStopBits_OnePointFive = 15,
+    kStopBits_Two = 20
+  };
+  enum FlowControl {
+    kFlowControl_None = 0,
+    kFlowControl_XonXoff = 1,
+    kFlowControl_RtsCts = 2,
+    kFlowControl_DtrDsr = 4
+  };
+  enum WriteBufferMode { kFlushOnAccess = 1, kFlushWhenFull = 2 };
+  enum Port { kOnboard = 0, kMXP = 1, kUSB = 2, kUSB1 = 2, kUSB2 = 3 };
+
+  SerialPort(int baudRate, Port port = kOnboard, int dataBits = 8,
+             Parity parity = kParity_None, StopBits stopBits = kStopBits_One);
+  ~SerialPort();
+
+  SerialPort(const SerialPort&) = delete;
+  SerialPort& operator=(const SerialPort&) = delete;
+
+  void SetFlowControl(FlowControl flowControl);
+  void EnableTermination(char terminator = '\n');
+  void DisableTermination();
+  int GetBytesReceived();
+  int Read(char* buffer, int count);
+  WPI_DEPRECATED(
+      "Potential for unexpected behavior. Please use StringRef overload for "
+      "custom length buffers using std::string")
+  int Write(const std::string& buffer, int count);
+  int Write(const char* buffer, int count);
+  int Write(llvm::StringRef buffer);
+  void SetTimeout(double timeout);
+  void SetReadBufferSize(int size);
+  void SetWriteBufferSize(int size);
+  void SetWriteBufferMode(WriteBufferMode mode);
+  void Flush();
+  void Reset();
+
+ private:
+  int m_resourceManagerHandle = 0;
+  int m_portHandle = 0;
+  bool m_consoleModeEnabled = false;
+  int m_port;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/Servo.h b/wpilibc/athena/include/Servo.h
new file mode 100644
index 0000000..7cac0ca
--- /dev/null
+++ b/wpilibc/athena/include/Servo.h
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SafePWM.h"
+#include "SpeedController.h"
+
+namespace frc {
+
+/**
+ * Standard hobby style servo.
+ *
+ * The range parameters default to the appropriate values for the Hitec HS-322HD
+ * servo provided
+ * in the FIRST Kit of Parts in 2008.
+ */
+class Servo : public SafePWM {
+ public:
+  explicit Servo(int channel);
+  virtual ~Servo();
+  void Set(double value);
+  void SetOffline();
+  double Get() const;
+  void SetAngle(double angle);
+  double GetAngle() const;
+  static double GetMaxAngle() { return kMaxServoAngle; }
+  static double GetMinAngle() { return kMinServoAngle; }
+
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew) override;
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+  std::shared_ptr<ITable> m_table;
+
+ private:
+  double GetServoAngleRange() const { return kMaxServoAngle - kMinServoAngle; }
+
+  static constexpr double kMaxServoAngle = 180.0;
+  static constexpr double kMinServoAngle = 0.0;
+
+  static constexpr double kDefaultMaxServoPWM = 2.4;
+  static constexpr double kDefaultMinServoPWM = .6;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/Solenoid.h b/wpilibc/athena/include/Solenoid.h
new file mode 100644
index 0000000..3ede182
--- /dev/null
+++ b/wpilibc/athena/include/Solenoid.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "LiveWindow/LiveWindowSendable.h"
+#include "SolenoidBase.h"
+#include "tables/ITableListener.h"
+
+namespace frc {
+
+/**
+ * Solenoid class for running high voltage Digital Output (PCM).
+ *
+ * The Solenoid class is typically used for pneumatics solenoids, but could be
+ * used for any device within the current spec of the PCM.
+ */
+class Solenoid : public SolenoidBase,
+                 public LiveWindowSendable,
+                 public ITableListener {
+ public:
+  explicit Solenoid(int channel);
+  Solenoid(int moduleNumber, int channel);
+  virtual ~Solenoid();
+  virtual void Set(bool on);
+  virtual bool Get() const;
+  bool IsBlackListed() const;
+
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew);
+  void UpdateTable();
+  void StartLiveWindowMode();
+  void StopLiveWindowMode();
+  std::string GetSmartDashboardType() const;
+  void InitTable(std::shared_ptr<ITable> subTable);
+  std::shared_ptr<ITable> GetTable() const;
+
+ private:
+  HAL_SolenoidHandle m_solenoidHandle = HAL_kInvalidHandle;
+  int m_channel;  ///< The channel on the module to control.
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/SolenoidBase.h b/wpilibc/athena/include/SolenoidBase.h
new file mode 100644
index 0000000..276f6e6
--- /dev/null
+++ b/wpilibc/athena/include/SolenoidBase.h
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include "SensorBase.h"
+
+namespace frc {
+
+/**
+ * SolenoidBase class is the common base class for the Solenoid and
+ * DoubleSolenoid classes.
+ */
+class SolenoidBase : public SensorBase {
+ public:
+  virtual ~SolenoidBase() = default;
+  int GetAll(int module = 0) const;
+
+  int GetPCMSolenoidBlackList(int module) const;
+  bool GetPCMSolenoidVoltageStickyFault(int module) const;
+  bool GetPCMSolenoidVoltageFault(int module) const;
+  void ClearAllPCMStickyFaults(int module);
+
+ protected:
+  explicit SolenoidBase(int pcmID);
+  static const int m_maxModules = 63;
+  static const int m_maxPorts = 8;
+  // static void* m_ports[m_maxModules][m_maxPorts];
+  int m_moduleNumber;  ///< Slot number where the module is plugged into
+                       /// the chassis.
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/Spark.h b/wpilibc/athena/include/Spark.h
new file mode 100644
index 0000000..8602dbc
--- /dev/null
+++ b/wpilibc/athena/include/Spark.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 "PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * REV Robotics Speed Controller
+ */
+class Spark : public PWMSpeedController {
+ public:
+  explicit Spark(int channel);
+  virtual ~Spark() = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/SpeedController.h b/wpilibc/athena/include/SpeedController.h
new file mode 100644
index 0000000..3458e7f
--- /dev/null
+++ b/wpilibc/athena/include/SpeedController.h
@@ -0,0 +1,57 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "PIDOutput.h"
+
+namespace frc {
+
+/**
+ * Interface for speed controlling devices.
+ */
+class SpeedController : public PIDOutput {
+ public:
+  virtual ~SpeedController() = default;
+  /**
+   * Common interface for setting the speed of a speed controller.
+   *
+   * @param speed The speed to set.  Value should be between -1.0 and 1.0.
+   */
+  virtual void Set(double speed) = 0;
+
+  /**
+   * Common interface for getting the current set speed of a speed controller.
+   *
+   * @return The current set speed.  Value is between -1.0 and 1.0.
+   */
+  virtual double Get() const = 0;
+
+  /**
+  * Common interface for inverting direction of a speed controller.
+  * @param isInverted The state of inversion, true is inverted.
+  */
+  virtual void SetInverted(bool isInverted) = 0;
+  /**
+
+   * Common interface for disabling a motor.
+   */
+  virtual void Disable() = 0;
+
+  /**
+   * Common interface for returning the inversion state of a speed controller.
+   * @return isInverted The state of inversion, true is inverted.
+   */
+  virtual bool GetInverted() const = 0;
+
+  /**
+   * Common interface to stop the motor until Set is called again.
+   */
+  virtual void StopMotor() = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/Talon.h b/wpilibc/athena/include/Talon.h
new file mode 100644
index 0000000..793d77b
--- /dev/null
+++ b/wpilibc/athena/include/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 "PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Cross the Road Electronics (CTRE) Talon and Talon SR Speed Controller
+ */
+class Talon : public PWMSpeedController {
+ public:
+  explicit Talon(int channel);
+  virtual ~Talon() = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/TalonSRX.h b/wpilibc/athena/include/TalonSRX.h
new file mode 100644
index 0000000..ecc5997
--- /dev/null
+++ b/wpilibc/athena/include/TalonSRX.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 "PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Cross the Road Electronics (CTRE) Talon SRX Speed Controller with PWM control
+ */
+class TalonSRX : public PWMSpeedController {
+ public:
+  explicit TalonSRX(int channel);
+  virtual ~TalonSRX() = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/Task.h b/wpilibc/athena/include/Task.h
new file mode 100644
index 0000000..646a400
--- /dev/null
+++ b/wpilibc/athena/include/Task.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <string>
+#include <thread>
+
+#include "ErrorBase.h"
+#include "HAL/HAL.h"
+#include "support/deprecated.h"
+
+namespace frc {
+
+/**
+ * Wrapper class around std::thread that allows changing thread priority
+ */
+class WPI_DEPRECATED(
+    "Task API scheduled for removal in 2018. Replace with std::thread, and use "
+    "Threads API for setting priority") Task : public ErrorBase {
+ public:
+  static const int kDefaultPriority = 60;
+
+  Task() = default;
+  Task(const Task&) = delete;
+  Task& operator=(const Task&) = delete;
+  Task& operator=(Task&& task);
+
+  template <class Function, class... Args>
+  Task(const std::string& name, Function&& function, Args&&... args);
+
+  virtual ~Task();
+
+  bool joinable() const noexcept;
+  void join();
+  void detach();
+  std::thread::id get_id() const noexcept;
+  std::thread::native_handle_type native_handle();
+
+  bool Verify();
+
+  int GetPriority();
+
+  bool SetPriority(int priority);
+
+  std::string GetName() const;
+
+ private:
+  std::thread m_thread;
+  std::string m_taskName;
+
+  typedef int32_t TASK_STATUS;
+
+  static constexpr int32_t TASK_OK = 0;
+  static constexpr int32_t TASK_ERROR = -1;
+  static constexpr int32_t TaskLib_ILLEGAL_PRIORITY = 22;  // 22 is EINVAL
+
+  bool HandleError(TASK_STATUS results);
+  TASK_STATUS VerifyTaskId();
+  TASK_STATUS GetTaskPriority(int32_t* priority);
+  TASK_STATUS SetTaskPriority(int32_t priority);
+};
+
+}  // namespace frc
+
+#include "Task.inc"
diff --git a/wpilibc/athena/include/Task.inc b/wpilibc/athena/include/Task.inc
new file mode 100644
index 0000000..e56b5ee
--- /dev/null
+++ b/wpilibc/athena/include/Task.inc
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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 <atomic>
+#include <iostream>
+#include <string>
+#include <utility>
+
+namespace frc {
+
+/**
+ * Create and launch a task.
+ *
+ * @param name The name of the task. "FRC_" will be prepended to the task name.
+ * @param function The address of the function to run as the new task.
+ * @param args A parameter pack of arguments to pass to the function.
+ */
+template <class Function, class... Args>
+Task::Task(const std::string& name, Function&& function, Args&&... args) {
+  m_taskName = "FRC_";
+  m_taskName += name;
+
+  std::cout << "[HAL] Starting task " << m_taskName << "..." << std::endl;
+
+  m_thread = std::thread(std::forward<std::decay_t<Function>>(function),
+                         std::forward<Args>(args)...);
+  // TODO: lvuser does not currently have permissions to set the priority.
+  // SetPriority(kDefaultPriority);
+
+  static std::atomic<int32_t> instances{0};
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_Task, instances, 0,
+             m_taskName.c_str());
+}
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/Threads.h b/wpilibc/athena/include/Threads.h
new file mode 100644
index 0000000..57c86cf
--- /dev/null
+++ b/wpilibc/athena/include/Threads.h
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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 <thread>
+
+namespace frc {
+
+int GetThreadPriority(std::thread& thread, bool* isRealTime);
+int GetCurrentThreadPriority(bool* isRealTime);
+bool SetThreadPriority(std::thread& thread, bool realTime, int priority);
+bool SetCurrentThreadPriority(bool realTime, int priority);
+}  // namespace frc
diff --git a/wpilibc/athena/include/Ultrasonic.h b/wpilibc/athena/include/Ultrasonic.h
new file mode 100644
index 0000000..f3a457c
--- /dev/null
+++ b/wpilibc/athena/include/Ultrasonic.h
@@ -0,0 +1,102 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <memory>
+#include <set>
+#include <string>
+#include <thread>
+
+#include "Counter.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "PIDSource.h"
+#include "SensorBase.h"
+
+namespace frc {
+
+class DigitalInput;
+class DigitalOutput;
+
+/**
+ * Ultrasonic rangefinder class.
+ * The Ultrasonic rangefinder measures absolute distance based on the round-trip
+ * time of a ping generated by the controller. These sensors use two
+ * transducers, a speaker and a microphone both tuned to the ultrasonic range. A
+ * common ultrasonic sensor, the Daventech SRF04 requires a short pulse to be
+ * generated on a digital channel. This causes the chirp to be emitted. A second
+ * line becomes high as the ping is transmitted and goes low when the echo is
+ * received. The time that the line is high determines the round trip distance
+ * (time of flight).
+ */
+class Ultrasonic : public SensorBase,
+                   public PIDSource,
+                   public LiveWindowSendable {
+ public:
+  enum DistanceUnit { kInches = 0, kMilliMeters = 1 };
+
+  Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel,
+             DistanceUnit units = kInches);
+
+  Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel,
+             DistanceUnit units = kInches);
+
+  Ultrasonic(std::shared_ptr<DigitalOutput> pingChannel,
+             std::shared_ptr<DigitalInput> echoChannel,
+             DistanceUnit units = kInches);
+  Ultrasonic(int pingChannel, int echoChannel, DistanceUnit units = kInches);
+  virtual ~Ultrasonic();
+
+  void Ping();
+  bool IsRangeValid() const;
+  static void SetAutomaticMode(bool enabling);
+  double GetRangeInches() const;
+  double GetRangeMM() const;
+  bool IsEnabled() const { return m_enabled; }
+  void SetEnabled(bool enable) { m_enabled = enable; }
+
+  double PIDGet() override;
+  void SetPIDSourceType(PIDSourceType pidSource) override;
+  void SetDistanceUnits(DistanceUnit units);
+  DistanceUnit GetDistanceUnits() const;
+
+  void UpdateTable() override;
+  void StartLiveWindowMode() override;
+  void StopLiveWindowMode() override;
+  std::string GetSmartDashboardType() const override;
+  void InitTable(std::shared_ptr<ITable> subTable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+
+ private:
+  void Initialize();
+
+  static void UltrasonicChecker();
+
+  // Time (sec) for the ping trigger pulse.
+  static constexpr double kPingTime = 10 * 1e-6;
+  // Priority that the ultrasonic round robin task runs.
+  static const int kPriority = 64;
+  // Max time (ms) between readings.
+  static constexpr double kMaxUltrasonicTime = 0.1;
+  static constexpr double kSpeedOfSoundInchesPerSec = 1130.0 * 12.0;
+
+  static std::thread
+      m_thread;  // thread doing the round-robin automatic sensing
+  static std::set<Ultrasonic*> m_sensors;       // ultrasonic sensors
+  static std::atomic<bool> m_automaticEnabled;  // automatic round robin mode
+
+  std::shared_ptr<DigitalOutput> m_pingChannel;
+  std::shared_ptr<DigitalInput> m_echoChannel;
+  bool m_enabled = false;
+  Counter m_counter;
+  DistanceUnit m_units;
+
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/Victor.h b/wpilibc/athena/include/Victor.h
new file mode 100644
index 0000000..2dbcb20
--- /dev/null
+++ b/wpilibc/athena/include/Victor.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Vex Robotics Victor 888 Speed Controller
+ *
+ * The Vex Robotics Victor 884 Speed Controller can also be used with this
+ * class but may need to be calibrated per the Victor 884 user manual.
+ */
+class Victor : public PWMSpeedController {
+ public:
+  explicit Victor(int channel);
+  virtual ~Victor() = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/VictorSP.h b/wpilibc/athena/include/VictorSP.h
new file mode 100644
index 0000000..539b27b
--- /dev/null
+++ b/wpilibc/athena/include/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 "PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Vex Robotics Victor SP Speed Controller
+ */
+class VictorSP : public PWMSpeedController {
+ public:
+  explicit VictorSP(int channel);
+  virtual ~VictorSP() = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/athena/include/WPILib.h b/wpilibc/athena/include/WPILib.h
new file mode 100644
index 0000000..5fe5c74
--- /dev/null
+++ b/wpilibc/athena/include/WPILib.h
@@ -0,0 +1,90 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ADXL345_I2C.h"
+#include "ADXL345_SPI.h"
+#include "ADXL362.h"
+#include "ADXRS450_Gyro.h"
+#include "AnalogAccelerometer.h"
+#include "AnalogGyro.h"
+#include "AnalogInput.h"
+#include "AnalogOutput.h"
+#include "AnalogPotentiometer.h"
+#include "AnalogTrigger.h"
+#include "AnalogTriggerOutput.h"
+#include "BuiltInAccelerometer.h"
+#include "Buttons/InternalButton.h"
+#include "Buttons/JoystickButton.h"
+#include "Buttons/NetworkButton.h"
+#include "CameraServer.h"
+#include "Commands/Command.h"
+#include "Commands/CommandGroup.h"
+#include "Commands/PIDCommand.h"
+#include "Commands/PIDSubsystem.h"
+#include "Commands/PrintCommand.h"
+#include "Commands/Scheduler.h"
+#include "Commands/StartCommand.h"
+#include "Commands/Subsystem.h"
+#include "Commands/WaitCommand.h"
+#include "Commands/WaitForChildren.h"
+#include "Commands/WaitUntilCommand.h"
+#include "Compressor.h"
+#include "ControllerPower.h"
+#include "Counter.h"
+#include "DigitalInput.h"
+#include "DigitalOutput.h"
+#include "DigitalSource.h"
+#include "DoubleSolenoid.h"
+#include "DriverStation.h"
+#include "Encoder.h"
+#include "ErrorBase.h"
+#include "Filters/LinearDigitalFilter.h"
+#include "GearTooth.h"
+#include "GenericHID.h"
+#include "I2C.h"
+#include "InterruptableSensorBase.h"
+#include "IterativeRobot.h"
+#include "Jaguar.h"
+#include "Joystick.h"
+#include "Notifier.h"
+#include "PIDController.h"
+#include "PIDOutput.h"
+#include "PIDSource.h"
+#include "PWM.h"
+#include "PWMSpeedController.h"
+#include "PowerDistributionPanel.h"
+#include "Preferences.h"
+#include "Relay.h"
+#include "RobotBase.h"
+#include "RobotDrive.h"
+#include "SD540.h"
+#include "SPI.h"
+#include "SampleRobot.h"
+#include "SensorBase.h"
+#include "SerialPort.h"
+#include "Servo.h"
+#include "SmartDashboard/SendableChooser.h"
+#include "SmartDashboard/SmartDashboard.h"
+#include "Solenoid.h"
+#include "Spark.h"
+#include "SpeedController.h"
+#include "Talon.h"
+#include "TalonSRX.h"
+#include "Threads.h"
+#include "Timer.h"
+#include "Ultrasonic.h"
+#include "Utility.h"
+#include "Victor.h"
+#include "VictorSP.h"
+#include "WPIErrors.h"
+#include "XboxController.h"
+#include "interfaces/Accelerometer.h"
+#include "interfaces/Gyro.h"
+#include "interfaces/Potentiometer.h"
+#include "vision/VisionRunner.h"
diff --git a/wpilibc/athena/include/vision/VisionPipeline.h b/wpilibc/athena/include/vision/VisionPipeline.h
new file mode 100644
index 0000000..bccd50b
--- /dev/null
+++ b/wpilibc/athena/include/vision/VisionPipeline.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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 cv {
+class Mat;
+}
+
+namespace frc {
+
+/**
+ * A vision pipeline is responsible for running a group of
+ * OpenCV algorithms to extract data from an image.
+ *
+ * @see VisionRunner
+ */
+class VisionPipeline {
+ public:
+  virtual ~VisionPipeline() = default;
+
+  /**
+   * Processes the image input and sets the result objects.
+   * Implementations should make these objects accessible.
+   */
+  virtual void Process(cv::Mat& mat) = 0;
+};
+}  // namespace frc
diff --git a/wpilibc/athena/include/vision/VisionRunner.h b/wpilibc/athena/include/vision/VisionRunner.h
new file mode 100644
index 0000000..76c1213
--- /dev/null
+++ b/wpilibc/athena/include/vision/VisionRunner.h
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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 <functional>
+#include <memory>
+
+#include "ErrorBase.h"
+#include "cscore.h"
+#include "vision/VisionPipeline.h"
+
+namespace frc {
+
+/**
+ * Non-template base class for VisionRunner.
+ */
+class VisionRunnerBase : public ErrorBase {
+ public:
+  explicit VisionRunnerBase(cs::VideoSource videoSource);
+  ~VisionRunnerBase() override;
+
+  VisionRunnerBase(const VisionRunnerBase&) = delete;
+  VisionRunnerBase& operator=(const VisionRunnerBase&) = delete;
+
+  void RunOnce();
+
+  void RunForever();
+
+ protected:
+  virtual void DoProcess(cv::Mat& image) = 0;
+
+ private:
+  std::unique_ptr<cv::Mat> m_image;
+  cs::CvSink m_cvSink;
+};
+
+/**
+ * A vision runner is a convenient wrapper object to make it easy to run vision
+ * pipelines from robot code. The easiest way to use this is to run it in a
+ * std::thread and use the listener to take snapshots of the pipeline's outputs.
+ *
+ * @see VisionPipeline
+ */
+template <typename T>
+class VisionRunner : public VisionRunnerBase {
+ public:
+  VisionRunner(cs::VideoSource videoSource, T* pipeline,
+               std::function<void(T&)> listener);
+  virtual ~VisionRunner() = default;
+
+ protected:
+  void DoProcess(cv::Mat& image) override;
+
+ private:
+  T* m_pipeline;
+  std::function<void(T&)> m_listener;
+};
+}  // namespace frc
+
+#include "VisionRunner.inc"
diff --git a/wpilibc/athena/include/vision/VisionRunner.inc b/wpilibc/athena/include/vision/VisionRunner.inc
new file mode 100644
index 0000000..991c898
--- /dev/null
+++ b/wpilibc/athena/include/vision/VisionRunner.inc
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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 {
+
+/**
+ * Creates a new vision runner. It will take images from the {@code
+ * videoSource}, send them to the {@code pipeline}, and call the {@code
+ * listener} when the pipeline has finished to alert user code when it is safe
+ * to access the pipeline's outputs.
+ *
+ * @param videoSource the video source to use to supply images for the pipeline
+ * @param pipeline    the vision pipeline to run
+ * @param listener    a function to call after the pipeline has finished
+ * running
+ */
+template <typename T>
+VisionRunner<T>::VisionRunner(cs::VideoSource videoSource, T* pipeline,
+                              std::function<void(T&)> listener)
+    : VisionRunnerBase(videoSource),
+      m_pipeline(pipeline),
+      m_listener(listener) {}
+
+template <typename T>
+void VisionRunner<T>::DoProcess(cv::Mat& image) {
+  m_pipeline->Process(image);
+  m_listener(*m_pipeline);
+}
+
+}  // namespace frc
diff --git a/wpilibc/athena/src/ADXL345_I2C.cpp b/wpilibc/athena/src/ADXL345_I2C.cpp
new file mode 100644
index 0000000..5179c1c
--- /dev/null
+++ b/wpilibc/athena/src/ADXL345_I2C.cpp
@@ -0,0 +1,98 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ADXL345_I2C.h"
+
+#include "HAL/HAL.h"
+#include "I2C.h"
+#include "LiveWindow/LiveWindow.h"
+
+using namespace frc;
+
+const int ADXL345_I2C::kAddress;
+const int ADXL345_I2C::kPowerCtlRegister;
+const int ADXL345_I2C::kDataFormatRegister;
+const int ADXL345_I2C::kDataRegister;
+constexpr double ADXL345_I2C::kGsPerLSB;
+
+/**
+ * Constructs the ADXL345 Accelerometer over I2C.
+ *
+ * @param port          The I2C port the accelerometer is attached to
+ * @param range         The range (+ or -) that the accelerometer will measure
+ * @param deviceAddress The I2C address of the accelerometer (0x1D or 0x53)
+ */
+ADXL345_I2C::ADXL345_I2C(I2C::Port port, Range range, int deviceAddress)
+    : m_i2c(port, deviceAddress) {
+  // Turn on the measurements
+  m_i2c.Write(kPowerCtlRegister, kPowerCtl_Measure);
+  // Specify the data format to read
+  SetRange(range);
+
+  HAL_Report(HALUsageReporting::kResourceType_ADXL345,
+             HALUsageReporting::kADXL345_I2C, 0);
+  LiveWindow::GetInstance()->AddSensor("ADXL345_I2C", port, this);
+}
+
+void ADXL345_I2C::SetRange(Range range) {
+  m_i2c.Write(kDataFormatRegister,
+              kDataFormat_FullRes | static_cast<uint8_t>(range));
+}
+
+double ADXL345_I2C::GetX() { return GetAcceleration(kAxis_X); }
+
+double ADXL345_I2C::GetY() { return GetAcceleration(kAxis_Y); }
+
+double ADXL345_I2C::GetZ() { return GetAcceleration(kAxis_Z); }
+
+/**
+ * Get the acceleration of one axis in Gs.
+ *
+ * @param axis The axis to read from.
+ * @return Acceleration of the ADXL345 in Gs.
+ */
+double ADXL345_I2C::GetAcceleration(ADXL345_I2C::Axes axis) {
+  int16_t rawAccel = 0;
+  m_i2c.Read(kDataRegister + static_cast<int>(axis), sizeof(rawAccel),
+             reinterpret_cast<uint8_t*>(&rawAccel));
+  return rawAccel * kGsPerLSB;
+}
+
+/**
+ * Get the acceleration of all axes in Gs.
+ *
+ * @return An object containing the acceleration measured on each axis of the
+ *         ADXL345 in Gs.
+ */
+ADXL345_I2C::AllAxes ADXL345_I2C::GetAccelerations() {
+  AllAxes data = AllAxes();
+  int16_t rawData[3];
+  m_i2c.Read(kDataRegister, sizeof(rawData),
+             reinterpret_cast<uint8_t*>(rawData));
+
+  data.XAxis = rawData[0] * kGsPerLSB;
+  data.YAxis = rawData[1] * kGsPerLSB;
+  data.ZAxis = rawData[2] * kGsPerLSB;
+  return data;
+}
+
+std::string ADXL345_I2C::GetSmartDashboardType() const {
+  return "3AxisAccelerometer";
+}
+
+void ADXL345_I2C::InitTable(std::shared_ptr<ITable> subtable) {
+  m_table = subtable;
+  UpdateTable();
+}
+
+void ADXL345_I2C::UpdateTable() {
+  m_table->PutNumber("X", GetX());
+  m_table->PutNumber("Y", GetY());
+  m_table->PutNumber("Z", GetZ());
+}
+
+std::shared_ptr<ITable> ADXL345_I2C::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/ADXL345_SPI.cpp b/wpilibc/athena/src/ADXL345_SPI.cpp
new file mode 100644
index 0000000..3fefa9f
--- /dev/null
+++ b/wpilibc/athena/src/ADXL345_SPI.cpp
@@ -0,0 +1,127 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ADXL345_SPI.h"
+
+#include "DigitalInput.h"
+#include "DigitalOutput.h"
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.h"
+
+using namespace frc;
+
+const int ADXL345_SPI::kPowerCtlRegister;
+const int ADXL345_SPI::kDataFormatRegister;
+const int ADXL345_SPI::kDataRegister;
+constexpr double ADXL345_SPI::kGsPerLSB;
+
+/**
+ * Constructor.
+ *
+ * @param port  The SPI port the accelerometer is attached to
+ * @param range The range (+ or -) that the accelerometer will measure
+ */
+ADXL345_SPI::ADXL345_SPI(SPI::Port port, ADXL345_SPI::Range range)
+    : m_spi(port) {
+  m_spi.SetClockRate(500000);
+  m_spi.SetMSBFirst();
+  m_spi.SetSampleDataOnFalling();
+  m_spi.SetClockActiveLow();
+  m_spi.SetChipSelectActiveHigh();
+
+  uint8_t commands[2];
+  // Turn on the measurements
+  commands[0] = kPowerCtlRegister;
+  commands[1] = kPowerCtl_Measure;
+  m_spi.Transaction(commands, commands, 2);
+
+  SetRange(range);
+
+  HAL_Report(HALUsageReporting::kResourceType_ADXL345,
+             HALUsageReporting::kADXL345_SPI);
+
+  LiveWindow::GetInstance()->AddSensor("ADXL345_SPI", port, this);
+}
+
+void ADXL345_SPI::SetRange(Range range) {
+  uint8_t commands[2];
+
+  // Specify the data format to read
+  commands[0] = kDataFormatRegister;
+  commands[1] = kDataFormat_FullRes | static_cast<uint8_t>(range & 0x03);
+  m_spi.Transaction(commands, commands, 2);
+}
+
+double ADXL345_SPI::GetX() { return GetAcceleration(kAxis_X); }
+
+double ADXL345_SPI::GetY() { return GetAcceleration(kAxis_Y); }
+
+double ADXL345_SPI::GetZ() { return GetAcceleration(kAxis_Z); }
+
+/**
+ * Get the acceleration of one axis in Gs.
+ *
+ * @param axis The axis to read from.
+ * @return Acceleration of the ADXL345 in Gs.
+ */
+double ADXL345_SPI::GetAcceleration(ADXL345_SPI::Axes axis) {
+  uint8_t buffer[3];
+  uint8_t command[3] = {0, 0, 0};
+  command[0] = (kAddress_Read | kAddress_MultiByte | kDataRegister) +
+               static_cast<uint8_t>(axis);
+  m_spi.Transaction(command, buffer, 3);
+
+  // Sensor is little endian... swap bytes
+  int16_t rawAccel = buffer[2] << 8 | buffer[1];
+  return rawAccel * kGsPerLSB;
+}
+
+/**
+ * Get the acceleration of all axes in Gs.
+ *
+ * @return An object containing the acceleration measured on each axis of the
+ *         ADXL345 in Gs.
+ */
+ADXL345_SPI::AllAxes ADXL345_SPI::GetAccelerations() {
+  AllAxes data = AllAxes();
+  uint8_t dataBuffer[7] = {0, 0, 0, 0, 0, 0, 0};
+  int16_t rawData[3];
+
+  // Select the data address.
+  dataBuffer[0] = (kAddress_Read | kAddress_MultiByte | kDataRegister);
+  m_spi.Transaction(dataBuffer, dataBuffer, 7);
+
+  for (int i = 0; i < 3; i++) {
+    // Sensor is little endian... swap bytes
+    rawData[i] = dataBuffer[i * 2 + 2] << 8 | dataBuffer[i * 2 + 1];
+  }
+
+  data.XAxis = rawData[0] * kGsPerLSB;
+  data.YAxis = rawData[1] * kGsPerLSB;
+  data.ZAxis = rawData[2] * kGsPerLSB;
+
+  return data;
+}
+
+std::string ADXL345_SPI::GetSmartDashboardType() const {
+  return "3AxisAccelerometer";
+}
+
+void ADXL345_SPI::InitTable(std::shared_ptr<ITable> subtable) {
+  m_table = subtable;
+  UpdateTable();
+}
+
+void ADXL345_SPI::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("X", GetX());
+    m_table->PutNumber("Y", GetY());
+    m_table->PutNumber("Z", GetZ());
+  }
+}
+
+std::shared_ptr<ITable> ADXL345_SPI::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/ADXL362.cpp b/wpilibc/athena/src/ADXL362.cpp
new file mode 100644
index 0000000..4a4d0c8
--- /dev/null
+++ b/wpilibc/athena/src/ADXL362.cpp
@@ -0,0 +1,182 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ADXL362.h"
+
+#include "DigitalInput.h"
+#include "DigitalOutput.h"
+#include "DriverStation.h"
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.h"
+
+using namespace frc;
+
+static int kRegWrite = 0x0A;
+static int kRegRead = 0x0B;
+
+static int kPartIdRegister = 0x02;
+static int kDataRegister = 0x0E;
+static int kFilterCtlRegister = 0x2C;
+static int kPowerCtlRegister = 0x2D;
+
+// static int kFilterCtl_Range2G = 0x00;
+// static int kFilterCtl_Range4G = 0x40;
+// static int kFilterCtl_Range8G = 0x80;
+static int kFilterCtl_ODR_100Hz = 0x03;
+
+static int kPowerCtl_UltraLowNoise = 0x20;
+// static int kPowerCtl_AutoSleep = 0x04;
+static int kPowerCtl_Measure = 0x02;
+
+/**
+ * Constructor.  Uses the onboard CS1.
+ *
+ * @param range The range (+ or -) that the accelerometer will measure.
+ */
+ADXL362::ADXL362(Range range) : ADXL362(SPI::Port::kOnboardCS1, range) {}
+
+/**
+ * Constructor.
+ *
+ * @param port  The SPI port the accelerometer is attached to
+ * @param range The range (+ or -) that the accelerometer will measure.
+ */
+ADXL362::ADXL362(SPI::Port port, Range range) : m_spi(port) {
+  m_spi.SetClockRate(3000000);
+  m_spi.SetMSBFirst();
+  m_spi.SetSampleDataOnFalling();
+  m_spi.SetClockActiveLow();
+  m_spi.SetChipSelectActiveLow();
+
+  // Validate the part ID
+  uint8_t commands[3];
+  commands[0] = kRegRead;
+  commands[1] = kPartIdRegister;
+  commands[2] = 0;
+  m_spi.Transaction(commands, commands, 3);
+  if (commands[2] != 0xF2) {
+    DriverStation::ReportError("could not find ADXL362");
+    m_gsPerLSB = 0.0;
+    return;
+  }
+
+  SetRange(range);
+
+  // Turn on the measurements
+  commands[0] = kRegWrite;
+  commands[1] = kPowerCtlRegister;
+  commands[2] = kPowerCtl_Measure | kPowerCtl_UltraLowNoise;
+  m_spi.Write(commands, 3);
+
+  HAL_Report(HALUsageReporting::kResourceType_ADXL362, port);
+
+  LiveWindow::GetInstance()->AddSensor("ADXL362", port, this);
+}
+
+void ADXL362::SetRange(Range range) {
+  if (m_gsPerLSB == 0.0) return;
+
+  uint8_t commands[3];
+
+  switch (range) {
+    case kRange_2G:
+      m_gsPerLSB = 0.001;
+      break;
+    case kRange_4G:
+      m_gsPerLSB = 0.002;
+      break;
+    case kRange_8G:
+    case kRange_16G:  // 16G not supported; treat as 8G
+      m_gsPerLSB = 0.004;
+      break;
+  }
+
+  // Specify the data format to read
+  commands[0] = kRegWrite;
+  commands[1] = kFilterCtlRegister;
+  commands[2] =
+      kFilterCtl_ODR_100Hz | static_cast<uint8_t>((range & 0x03) << 6);
+  m_spi.Write(commands, 3);
+}
+
+double ADXL362::GetX() { return GetAcceleration(kAxis_X); }
+
+double ADXL362::GetY() { return GetAcceleration(kAxis_Y); }
+
+double ADXL362::GetZ() { return GetAcceleration(kAxis_Z); }
+
+/**
+ * Get the acceleration of one axis in Gs.
+ *
+ * @param axis The axis to read from.
+ * @return Acceleration of the ADXL362 in Gs.
+ */
+double ADXL362::GetAcceleration(ADXL362::Axes axis) {
+  if (m_gsPerLSB == 0.0) return 0.0;
+
+  uint8_t buffer[4];
+  uint8_t command[4] = {0, 0, 0, 0};
+  command[0] = kRegRead;
+  command[1] = kDataRegister + static_cast<uint8_t>(axis);
+  m_spi.Transaction(command, buffer, 4);
+
+  // Sensor is little endian... swap bytes
+  int16_t rawAccel = buffer[3] << 8 | buffer[2];
+  return rawAccel * m_gsPerLSB;
+}
+
+/**
+ * Get the acceleration of all axes in Gs.
+ *
+ * @return An object containing the acceleration measured on each axis of the
+ *         ADXL362 in Gs.
+ */
+ADXL362::AllAxes ADXL362::GetAccelerations() {
+  AllAxes data = AllAxes();
+  if (m_gsPerLSB == 0.0) {
+    data.XAxis = data.YAxis = data.ZAxis = 0.0;
+    return data;
+  }
+
+  uint8_t dataBuffer[8] = {0, 0, 0, 0, 0, 0, 0, 0};
+  int16_t rawData[3];
+
+  // Select the data address.
+  dataBuffer[0] = kRegRead;
+  dataBuffer[1] = kDataRegister;
+  m_spi.Transaction(dataBuffer, dataBuffer, 8);
+
+  for (int i = 0; i < 3; i++) {
+    // Sensor is little endian... swap bytes
+    rawData[i] = dataBuffer[i * 2 + 3] << 8 | dataBuffer[i * 2 + 2];
+  }
+
+  data.XAxis = rawData[0] * m_gsPerLSB;
+  data.YAxis = rawData[1] * m_gsPerLSB;
+  data.ZAxis = rawData[2] * m_gsPerLSB;
+
+  return data;
+}
+
+std::string ADXL362::GetSmartDashboardType() const {
+  return "3AxisAccelerometer";
+}
+
+void ADXL362::InitTable(std::shared_ptr<ITable> subtable) {
+  m_table = subtable;
+  UpdateTable();
+}
+
+void ADXL362::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("X", GetX());
+    m_table->PutNumber("Y", GetY());
+    m_table->PutNumber("Z", GetZ());
+  }
+}
+
+std::shared_ptr<ITable> ADXL362::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/ADXRS450_Gyro.cpp b/wpilibc/athena/src/ADXRS450_Gyro.cpp
new file mode 100644
index 0000000..fb4a62f
--- /dev/null
+++ b/wpilibc/athena/src/ADXRS450_Gyro.cpp
@@ -0,0 +1,154 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ADXRS450_Gyro.h"
+
+#include "DriverStation.h"
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.h"
+#include "Timer.h"
+
+using namespace frc;
+
+static constexpr double kSamplePeriod = 0.001;
+static constexpr double kCalibrationSampleTime = 5.0;
+static constexpr double kDegreePerSecondPerLSB = 0.0125;
+
+static constexpr int kRateRegister = 0x00;
+static constexpr int kTemRegister = 0x02;
+static constexpr int kLoCSTRegister = 0x04;
+static constexpr int kHiCSTRegister = 0x06;
+static constexpr int kQuadRegister = 0x08;
+static constexpr int kFaultRegister = 0x0A;
+static constexpr int kPIDRegister = 0x0C;
+static constexpr int kSNHighRegister = 0x0E;
+static constexpr int kSNLowRegister = 0x10;
+
+/**
+ * Initialize the gyro.
+ *
+ * Calibrate the gyro by running for a number of samples and computing the
+ * center value. Then use the center value as the Accumulator center value for
+ * subsequent measurements.
+ *
+ * It's important to make sure that the robot is not moving while the centering
+ * calculations are in progress, this is typically done when the robot is first
+ * turned on while it's sitting at rest before the competition starts.
+ */
+void ADXRS450_Gyro::Calibrate() {
+  Wait(0.1);
+
+  m_spi.SetAccumulatorCenter(0);
+  m_spi.ResetAccumulator();
+
+  Wait(kCalibrationSampleTime);
+
+  m_spi.SetAccumulatorCenter(static_cast<int>(m_spi.GetAccumulatorAverage()));
+  m_spi.ResetAccumulator();
+}
+
+/**
+ * Gyro constructor on onboard CS0.
+ */
+ADXRS450_Gyro::ADXRS450_Gyro() : ADXRS450_Gyro(SPI::kOnboardCS0) {}
+
+/**
+ * Gyro constructor on the specified SPI port.
+ *
+ * @param port The SPI port the gyro is attached to.
+ */
+ADXRS450_Gyro::ADXRS450_Gyro(SPI::Port port) : m_spi(port) {
+  m_spi.SetClockRate(3000000);
+  m_spi.SetMSBFirst();
+  m_spi.SetSampleDataOnRising();
+  m_spi.SetClockActiveHigh();
+  m_spi.SetChipSelectActiveLow();
+
+  // Validate the part ID
+  if ((ReadRegister(kPIDRegister) & 0xff00) != 0x5200) {
+    DriverStation::ReportError("could not find ADXRS450 gyro");
+    return;
+  }
+
+  m_spi.InitAccumulator(kSamplePeriod, 0x20000000u, 4, 0x0c00000eu, 0x04000000u,
+                        10u, 16u, true, true);
+
+  Calibrate();
+
+  HAL_Report(HALUsageReporting::kResourceType_ADXRS450, port);
+  LiveWindow::GetInstance()->AddSensor("ADXRS450_Gyro", port, this);
+}
+
+static bool CalcParity(int v) {
+  bool parity = false;
+  while (v != 0) {
+    parity = !parity;
+    v = v & (v - 1);
+  }
+  return parity;
+}
+
+static inline int BytesToIntBE(uint8_t* buf) {
+  int result = static_cast<int>(buf[0]) << 24;
+  result |= static_cast<int>(buf[1]) << 16;
+  result |= static_cast<int>(buf[2]) << 8;
+  result |= static_cast<int>(buf[3]);
+  return result;
+}
+
+uint16_t ADXRS450_Gyro::ReadRegister(int reg) {
+  int cmd = 0x80000000 | static_cast<int>(reg) << 17;
+  if (!CalcParity(cmd)) cmd |= 1u;
+
+  // big endian
+  uint8_t buf[4] = {static_cast<uint8_t>((cmd >> 24) & 0xff),
+                    static_cast<uint8_t>((cmd >> 16) & 0xff),
+                    static_cast<uint8_t>((cmd >> 8) & 0xff),
+                    static_cast<uint8_t>(cmd & 0xff)};
+
+  m_spi.Write(buf, 4);
+  m_spi.Read(false, buf, 4);
+  if ((buf[0] & 0xe0) == 0) return 0;  // error, return 0
+  return static_cast<uint16_t>((BytesToIntBE(buf) >> 5) & 0xffff);
+}
+
+/**
+ * Reset the gyro.
+ *
+ * Resets the gyro to a heading of zero. This can be used if there is
+ * significant drift in the gyro and it needs to be recalibrated after it has
+ * been running.
+ */
+void ADXRS450_Gyro::Reset() { m_spi.ResetAccumulator(); }
+
+/**
+ * Return the actual angle in degrees that the robot is currently facing.
+ *
+ * The angle is based on the current accumulator value corrected by the
+ * oversampling rate, the gyro type and the A/D calibration values.
+ * The angle is continuous, that is it will continue from 360->361 degrees. This
+ * allows algorithms that wouldn't want to see a discontinuity in the gyro
+ * output as it sweeps from 360 to 0 on the second time around.
+ *
+ * @return the current heading of the robot in degrees. This heading is based on
+ *         integration of the returned rate from the gyro.
+ */
+double ADXRS450_Gyro::GetAngle() const {
+  return m_spi.GetAccumulatorValue() * kDegreePerSecondPerLSB * kSamplePeriod;
+}
+
+/**
+ * Return the rate of rotation of the gyro
+ *
+ * The rate is based on the most recent reading of the gyro analog value
+ *
+ * @return the current rate in degrees per second
+ */
+double ADXRS450_Gyro::GetRate() const {
+  return static_cast<double>(m_spi.GetAccumulatorLastValue()) *
+         kDegreePerSecondPerLSB;
+}
diff --git a/wpilibc/athena/src/AnalogAccelerometer.cpp b/wpilibc/athena/src/AnalogAccelerometer.cpp
new file mode 100644
index 0000000..6b2e1e9
--- /dev/null
+++ b/wpilibc/athena/src/AnalogAccelerometer.cpp
@@ -0,0 +1,139 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "AnalogAccelerometer.h"
+
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Common function for initializing the accelerometer.
+ */
+void AnalogAccelerometer::InitAccelerometer() {
+  HAL_Report(HALUsageReporting::kResourceType_Accelerometer,
+             m_analogInput->GetChannel());
+  LiveWindow::GetInstance()->AddSensor("Accelerometer",
+                                       m_analogInput->GetChannel(), this);
+}
+
+/**
+ * Create a new instance of an accelerometer.
+ *
+ * The constructor allocates desired analog input.
+ *
+ * @param channel The channel number for the analog input the accelerometer is
+ *                connected to
+ */
+AnalogAccelerometer::AnalogAccelerometer(int channel) {
+  m_analogInput = std::make_shared<AnalogInput>(channel);
+  InitAccelerometer();
+}
+
+/**
+ * Create a new instance of Accelerometer from an existing AnalogInput.
+ *
+ * Make a new instance of accelerometer given an AnalogInput. This is
+ * particularly useful if the port is going to be read as an analog channel as
+ * well as through the Accelerometer class.
+ *
+ * @param channel The existing AnalogInput object for the analog input the
+ *                accelerometer is connected to
+ */
+AnalogAccelerometer::AnalogAccelerometer(AnalogInput* channel)
+    : m_analogInput(channel, NullDeleter<AnalogInput>()) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitAccelerometer();
+  }
+}
+
+/**
+ * Create a new instance of Accelerometer from an existing AnalogInput.
+ *
+ * Make a new instance of accelerometer given an AnalogInput. This is
+ * particularly useful if the port is going to be read as an analog channel as
+ * well as through the Accelerometer class.
+ *
+ * @param channel The existing AnalogInput object for the analog input the
+ *                accelerometer is connected to
+ */
+AnalogAccelerometer::AnalogAccelerometer(std::shared_ptr<AnalogInput> channel)
+    : m_analogInput(channel) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitAccelerometer();
+  }
+}
+
+/**
+ * Return the acceleration in Gs.
+ *
+ * The acceleration is returned units of Gs.
+ *
+ * @return The current acceleration of the sensor in Gs.
+ */
+double AnalogAccelerometer::GetAcceleration() const {
+  return (m_analogInput->GetAverageVoltage() - m_zeroGVoltage) / m_voltsPerG;
+}
+
+/**
+ * Set the accelerometer sensitivity.
+ *
+ * This sets the sensitivity of the accelerometer used for calculating the
+ * acceleration. The sensitivity varies by accelerometer model. There are
+ * constants defined for various models.
+ *
+ * @param sensitivity The sensitivity of accelerometer in Volts per G.
+ */
+void AnalogAccelerometer::SetSensitivity(double sensitivity) {
+  m_voltsPerG = sensitivity;
+}
+
+/**
+ * Set the voltage that corresponds to 0 G.
+ *
+ * The zero G voltage varies by accelerometer model. There are constants defined
+ * for various models.
+ *
+ * @param zero The zero G voltage.
+ */
+void AnalogAccelerometer::SetZero(double zero) { m_zeroGVoltage = zero; }
+
+/**
+ * Get the Acceleration for the PID Source parent.
+ *
+ * @return The current acceleration in Gs.
+ */
+double AnalogAccelerometer::PIDGet() { return GetAcceleration(); }
+
+void AnalogAccelerometer::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", GetAcceleration());
+  }
+}
+
+void AnalogAccelerometer::StartLiveWindowMode() {}
+
+void AnalogAccelerometer::StopLiveWindowMode() {}
+
+std::string AnalogAccelerometer::GetSmartDashboardType() const {
+  return "Accelerometer";
+}
+
+void AnalogAccelerometer::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> AnalogAccelerometer::GetTable() const {
+  return m_table;
+}
diff --git a/wpilibc/athena/src/AnalogGyro.cpp b/wpilibc/athena/src/AnalogGyro.cpp
new file mode 100644
index 0000000..d3e2cc6
--- /dev/null
+++ b/wpilibc/athena/src/AnalogGyro.cpp
@@ -0,0 +1,284 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "AnalogGyro.h"
+#include "HAL/AnalogGyro.h"
+
+#include <climits>
+
+#include "AnalogInput.h"
+#include "HAL/Errors.h"
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.h"
+#include "Timer.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+const int AnalogGyro::kOversampleBits;
+const int AnalogGyro::kAverageBits;
+constexpr double AnalogGyro::kSamplesPerSecond;
+constexpr double AnalogGyro::kCalibrationSampleTime;
+constexpr double AnalogGyro::kDefaultVoltsPerDegreePerSecond;
+
+/**
+ * Gyro constructor using the Analog Input channel number.
+ *
+ * @param channel The analog channel the gyro is connected to. Gyros can only
+ *                be used on on-board Analog Inputs 0-1.
+ */
+AnalogGyro::AnalogGyro(int channel)
+    : AnalogGyro(std::make_shared<AnalogInput>(channel)) {}
+
+/**
+ * Gyro constructor with a precreated AnalogInput object.
+ *
+ * Use this constructor when the analog channel needs to be shared.
+ * This object will not clean up the AnalogInput object when using this
+ * constructor.
+ *
+ * Gyros can only be used on on-board channels 0-1.
+ *
+ * @param channel A pointer to the AnalogInput object that the gyro is
+ *                connected to.
+ */
+AnalogGyro::AnalogGyro(AnalogInput* channel)
+    : AnalogGyro(
+          std::shared_ptr<AnalogInput>(channel, NullDeleter<AnalogInput>())) {}
+
+/**
+ * Gyro constructor with a precreated AnalogInput object.
+ *
+ * Use this constructor when the analog channel needs to be shared.
+ * This object will not clean up the AnalogInput object when using this
+ * constructor.
+ *
+ * @param channel A pointer to the AnalogInput object that the gyro is
+ *                connected to.
+ */
+AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel)
+    : m_analog(channel) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitGyro();
+    Calibrate();
+  }
+}
+
+/**
+ * Gyro constructor using the Analog Input channel number with parameters for
+ * presetting the center and offset values. Bypasses calibration.
+ *
+ * @param channel The analog channel the gyro is connected to. Gyros can only
+ *                be used on on-board Analog Inputs 0-1.
+ * @param center  Preset uncalibrated value to use as the accumulator center
+ *                value.
+ * @param offset  Preset uncalibrated value to use as the gyro offset.
+ */
+AnalogGyro::AnalogGyro(int channel, int center, double offset) {
+  m_analog = std::make_shared<AnalogInput>(channel);
+  InitGyro();
+  int32_t status = 0;
+  HAL_SetAnalogGyroParameters(m_gyroHandle, kDefaultVoltsPerDegreePerSecond,
+                              offset, center, &status);
+  if (status != 0) {
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+    m_gyroHandle = HAL_kInvalidHandle;
+    return;
+  }
+  Reset();
+}
+
+/**
+ * Gyro constructor with a precreated AnalogInput object and calibrated
+ * parameters.
+ *
+ * Use this constructor when the analog channel needs to be shared.
+ * This object will not clean up the AnalogInput object when using this
+ * constructor.
+ *
+ * @param channel A pointer to the AnalogInput object that the gyro is
+ *                connected to.
+ */
+AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel, int center,
+                       double offset)
+    : m_analog(channel) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitGyro();
+    int32_t status = 0;
+    HAL_SetAnalogGyroParameters(m_gyroHandle, kDefaultVoltsPerDegreePerSecond,
+                                offset, center, &status);
+    if (status != 0) {
+      wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+      m_gyroHandle = HAL_kInvalidHandle;
+      return;
+    }
+    Reset();
+  }
+}
+
+/**
+ * AnalogGyro Destructor
+ *
+ */
+AnalogGyro::~AnalogGyro() { HAL_FreeAnalogGyro(m_gyroHandle); }
+
+/**
+ * Reset the gyro.
+ *
+ * Resets the gyro to a heading of zero. This can be used if there is
+ * significant drift in the gyro and it needs to be recalibrated after it has
+ * been running.
+ */
+void AnalogGyro::Reset() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_ResetAnalogGyro(m_gyroHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Initialize the gyro.  Calibration is handled by Calibrate().
+ */
+void AnalogGyro::InitGyro() {
+  if (StatusIsFatal()) return;
+  if (m_gyroHandle == HAL_kInvalidHandle) {
+    int32_t status = 0;
+    m_gyroHandle = HAL_InitializeAnalogGyro(m_analog->m_port, &status);
+    if (status == PARAMETER_OUT_OF_RANGE) {
+      wpi_setWPIErrorWithContext(ParameterOutOfRange,
+                                 " channel (must be accumulator channel)");
+      m_analog = nullptr;
+      m_gyroHandle = HAL_kInvalidHandle;
+      return;
+    }
+    if (status != 0) {
+      wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+      m_analog = nullptr;
+      m_gyroHandle = HAL_kInvalidHandle;
+      return;
+    }
+  }
+
+  int32_t status = 0;
+  HAL_SetupAnalogGyro(m_gyroHandle, &status);
+  if (status != 0) {
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+    m_analog = nullptr;
+    m_gyroHandle = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel());
+  LiveWindow::GetInstance()->AddSensor("AnalogGyro", m_analog->GetChannel(),
+                                       this);
+}
+
+void AnalogGyro::Calibrate() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_CalibrateAnalogGyro(m_gyroHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Return the actual angle in degrees that the robot is currently facing.
+ *
+ * The angle is based on the current accumulator value corrected by the
+ * oversampling rate, the gyro type and the A/D calibration values.
+ * The angle is continuous, that is it will continue from 360->361 degrees. This
+ * allows algorithms that wouldn't want to see a discontinuity in the gyro
+ * output as it sweeps from 360 to 0 on the second time around.
+ *
+ * @return the current heading of the robot in degrees. This heading is based on
+ *         integration of the returned rate from the gyro.
+ */
+double AnalogGyro::GetAngle() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetAnalogGyroAngle(m_gyroHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Return the rate of rotation of the gyro
+ *
+ * The rate is based on the most recent reading of the gyro analog value
+ *
+ * @return the current rate in degrees per second
+ */
+double AnalogGyro::GetRate() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetAnalogGyroRate(m_gyroHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Return the gyro offset value. If run after calibration,
+ * the offset value can be used as a preset later.
+ *
+ * @return the current offset value
+ */
+double AnalogGyro::GetOffset() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetAnalogGyroOffset(m_gyroHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Return the gyro center value. If run after calibration,
+ * the center value can be used as a preset later.
+ *
+ * @return the current center value
+ */
+int AnalogGyro::GetCenter() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetAnalogGyroCenter(m_gyroHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Set the gyro sensitivity.
+ *
+ * This takes the number of volts/degree/second sensitivity of the gyro and uses
+ * it in subsequent calculations to allow the code to work with multiple gyros.
+ * This value is typically found in the gyro datasheet.
+ *
+ * @param voltsPerDegreePerSecond The sensitivity in Volts/degree/second
+ */
+void AnalogGyro::SetSensitivity(double voltsPerDegreePerSecond) {
+  int32_t status = 0;
+  HAL_SetAnalogGyroVoltsPerDegreePerSecond(m_gyroHandle,
+                                           voltsPerDegreePerSecond, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Set the size of the neutral zone.
+ *
+ * Any voltage from the gyro less than this amount from the center is
+ * considered stationary.  Setting a deadband will decrease the amount of drift
+ * when the gyro isn't rotating, but will make it less accurate.
+ *
+ * @param volts The size of the deadband in volts
+ */
+void AnalogGyro::SetDeadband(double volts) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogGyroDeadband(m_gyroHandle, volts, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
diff --git a/wpilibc/athena/src/AnalogInput.cpp b/wpilibc/athena/src/AnalogInput.cpp
new file mode 100644
index 0000000..d370c3a
--- /dev/null
+++ b/wpilibc/athena/src/AnalogInput.cpp
@@ -0,0 +1,438 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "AnalogInput.h"
+#include "HAL/AnalogInput.h"
+
+#include <sstream>
+
+#include "HAL/AnalogAccumulator.h"
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "LiveWindow/LiveWindow.h"
+#include "Timer.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+const int AnalogInput::kAccumulatorModuleNumber;
+const int AnalogInput::kAccumulatorNumChannels;
+const int AnalogInput::kAccumulatorChannels[] = {0, 1};
+
+/**
+ * Construct an analog input.
+ *
+ * @param channel The channel number on the roboRIO to represent. 0-3 are
+ *                on-board 4-7 are on the MXP port.
+ */
+AnalogInput::AnalogInput(int channel) {
+  std::stringstream buf;
+  buf << "Analog Input " << channel;
+
+  if (!SensorBase::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;
+  }
+
+  LiveWindow::GetInstance()->AddSensor("AnalogInput", channel, this);
+  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;
+}
+
+/**
+ * Is the channel attached to an accumulator.
+ *
+ * @return The analog input is attached to an accumulator.
+ */
+bool AnalogInput::IsAccumulatorChannel() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool isAccum = HAL_IsAccumulatorChannel(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return isAccum;
+}
+
+/**
+ * Initialize the accumulator.
+ */
+void AnalogInput::InitAccumulator() {
+  if (StatusIsFatal()) return;
+  m_accumulatorOffset = 0;
+  int32_t status = 0;
+  HAL_InitAccumulator(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Set an initial value for the accumulator.
+ *
+ * This will be added to all values returned to the user.
+ *
+ * @param initialValue The value that the accumulator should start from when
+ *                     reset.
+ */
+void AnalogInput::SetAccumulatorInitialValue(int64_t initialValue) {
+  if (StatusIsFatal()) return;
+  m_accumulatorOffset = initialValue;
+}
+
+/**
+ * Resets the accumulator to the initial value.
+ */
+void AnalogInput::ResetAccumulator() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_ResetAccumulator(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  if (!StatusIsFatal()) {
+    // Wait until the next sample, so the next call to GetAccumulator*()
+    // won't have old values.
+    const double sampleTime = 1.0 / GetSampleRate();
+    const double overSamples = 1 << GetOversampleBits();
+    const double averageSamples = 1 << GetAverageBits();
+    Wait(sampleTime * overSamples * averageSamples);
+  }
+}
+
+/**
+ * Set the center value of the accumulator.
+ *
+ * The center value is subtracted from each A/D value before it is added to the
+ * accumulator. This is used for the center value of devices like gyros and
+ * accelerometers to take the device offset into account when integrating.
+ *
+ * This center value is based on the output of the oversampled and averaged
+ * source from the accumulator channel. Because of this, any non-zero
+ * oversample bits will affect the size of the value for this field.
+ */
+void AnalogInput::SetAccumulatorCenter(int center) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAccumulatorCenter(m_port, center, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Set the accumulator's deadband.
+ */
+void AnalogInput::SetAccumulatorDeadband(int deadband) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAccumulatorDeadband(m_port, deadband, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Read the accumulated value.
+ *
+ * Read the value that has been accumulating.
+ * The accumulator is attached after the oversample and average engine.
+ *
+ * @return The 64-bit value accumulated since the last Reset().
+ */
+int64_t AnalogInput::GetAccumulatorValue() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int64_t value = HAL_GetAccumulatorValue(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value + m_accumulatorOffset;
+}
+
+/**
+ * Read the number of accumulated values.
+ *
+ * Read the count of the accumulated values since the accumulator was last
+ * Reset().
+ *
+ * @return The number of times samples from the channel were accumulated.
+ */
+int64_t AnalogInput::GetAccumulatorCount() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int64_t count = HAL_GetAccumulatorCount(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return count;
+}
+
+/**
+ * Read the accumulated value and the number of accumulated values atomically.
+ *
+ * This function reads the value and count from the FPGA atomically.
+ * This can be used for averaging.
+ *
+ * @param value Reference to the 64-bit accumulated output.
+ * @param count Reference to the number of accumulation cycles.
+ */
+void AnalogInput::GetAccumulatorOutput(int64_t& value, int64_t& count) const {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_GetAccumulatorOutput(m_port, &value, &count, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  value += m_accumulatorOffset;
+}
+
+/**
+ * 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;
+}
+
+/**
+ * Get the Average value for the PID Source base object.
+ *
+ * @return The average voltage.
+ */
+double AnalogInput::PIDGet() {
+  if (StatusIsFatal()) return 0.0;
+  return GetAverageVoltage();
+}
+
+void AnalogInput::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", GetAverageVoltage());
+  }
+}
+
+void AnalogInput::StartLiveWindowMode() {}
+
+void AnalogInput::StopLiveWindowMode() {}
+
+std::string AnalogInput::GetSmartDashboardType() const {
+  return "Analog Input";
+}
+
+void AnalogInput::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> AnalogInput::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/AnalogOutput.cpp b/wpilibc/athena/src/AnalogOutput.cpp
new file mode 100644
index 0000000..3905ae1
--- /dev/null
+++ b/wpilibc/athena/src/AnalogOutput.cpp
@@ -0,0 +1,112 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "AnalogOutput.h"
+
+#include <limits>
+#include <sstream>
+
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "LiveWindow/LiveWindow.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Construct an analog output on the given channel.
+ *
+ * All analog outputs are located on the MXP port.
+ *
+ * @param channel The channel number on the roboRIO to represent.
+ */
+AnalogOutput::AnalogOutput(int channel) {
+  std::stringstream buf;
+  buf << "analog input " << channel;
+
+  if (!SensorBase::CheckAnalogOutputChannel(channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    m_channel = std::numeric_limits<int>::max();
+    m_port = HAL_kInvalidHandle;
+    return;
+  }
+
+  m_channel = channel;
+
+  HAL_PortHandle port = HAL_GetPort(m_channel);
+  int32_t status = 0;
+  m_port = HAL_InitializeAnalogOutputPort(port, &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumAnalogOutputs(), channel,
+                                 HAL_GetErrorMessage(status));
+    m_channel = std::numeric_limits<int>::max();
+    m_port = HAL_kInvalidHandle;
+    return;
+  }
+
+  LiveWindow::GetInstance()->AddActuator("AnalogOutput", m_channel, this);
+  HAL_Report(HALUsageReporting::kResourceType_AnalogOutput, m_channel);
+}
+
+/**
+ * Destructor.
+ *
+ * Frees analog output resource.
+ */
+AnalogOutput::~AnalogOutput() { HAL_FreeAnalogOutputPort(m_port); }
+
+/**
+ * Get the channel of this AnalogOutput.
+ */
+int AnalogOutput::GetChannel() { return m_channel; }
+
+/**
+ * Set the value of the analog output.
+ *
+ * @param voltage The output value in Volts, from 0.0 to +5.0
+ */
+void AnalogOutput::SetVoltage(double voltage) {
+  int32_t status = 0;
+  HAL_SetAnalogOutput(m_port, voltage, &status);
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Get the voltage of the analog output
+ *
+ * @return The value in Volts, from 0.0 to +5.0
+ */
+double AnalogOutput::GetVoltage() const {
+  int32_t status = 0;
+  double voltage = HAL_GetAnalogOutput(m_port, &status);
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  return voltage;
+}
+
+void AnalogOutput::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", GetVoltage());
+  }
+}
+
+void AnalogOutput::StartLiveWindowMode() {}
+
+void AnalogOutput::StopLiveWindowMode() {}
+
+std::string AnalogOutput::GetSmartDashboardType() const {
+  return "Analog Output";
+}
+
+void AnalogOutput::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> AnalogOutput::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/AnalogPotentiometer.cpp b/wpilibc/athena/src/AnalogPotentiometer.cpp
new file mode 100644
index 0000000..7afc247
--- /dev/null
+++ b/wpilibc/athena/src/AnalogPotentiometer.cpp
@@ -0,0 +1,102 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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 "AnalogPotentiometer.h"
+
+#include "ControllerPower.h"
+
+using namespace frc;
+
+/**
+ * Construct an Analog Potentiometer object from 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.
+ * @param fullRange The angular value (in desired units) representing the full
+ *                  0-5V range of the input.
+ * @param offset    The angular value (in desired units) representing the
+ *                  angular output at 0V.
+ */
+AnalogPotentiometer::AnalogPotentiometer(int channel, double fullRange,
+                                         double offset)
+    : m_analog_input(std::make_unique<AnalogInput>(channel)),
+      m_fullRange(fullRange),
+      m_offset(offset) {}
+
+/**
+ * Construct an Analog Potentiometer object from an existing Analog Input
+ * pointer.
+ *
+ * @param channel   The existing Analog Input pointer
+ * @param fullRange The angular value (in desired units) representing the full
+ *                  0-5V range of the input.
+ * @param offset    The angular value (in desired units) representing the
+ *                  angular output at 0V.
+ */
+AnalogPotentiometer::AnalogPotentiometer(AnalogInput* input, double fullRange,
+                                         double offset)
+    : m_analog_input(input, NullDeleter<AnalogInput>()),
+      m_fullRange(fullRange),
+      m_offset(offset) {}
+
+/**
+ * Construct an Analog Potentiometer object from an existing Analog Input
+ * pointer.
+ *
+ * @param channel   The existing Analog Input pointer
+ * @param fullRange The angular value (in desired units) representing the full
+ *                  0-5V range of the input.
+ * @param offset    The angular value (in desired units) representing the
+ *                  angular output at 0V.
+ */
+AnalogPotentiometer::AnalogPotentiometer(std::shared_ptr<AnalogInput> input,
+                                         double fullRange, double offset)
+    : m_analog_input(input), m_fullRange(fullRange), m_offset(offset) {}
+
+/**
+ * Get the current reading of the potentiometer.
+ *
+ * @return The current position of the potentiometer (in the units used for
+ *         fullRange and offset).
+ */
+double AnalogPotentiometer::Get() const {
+  return (m_analog_input->GetVoltage() / ControllerPower::GetVoltage5V()) *
+             m_fullRange +
+         m_offset;
+}
+
+/**
+ * Implement the PIDSource interface.
+ *
+ * @return The current reading.
+ */
+double AnalogPotentiometer::PIDGet() { return Get(); }
+
+/**
+ * @return the Smart Dashboard Type
+ */
+std::string AnalogPotentiometer::GetSmartDashboardType() const {
+  return "Analog Input";
+}
+
+/**
+ * Live Window code, only does anything if live window is activated.
+ */
+void AnalogPotentiometer::InitTable(std::shared_ptr<ITable> subtable) {
+  m_table = subtable;
+  UpdateTable();
+}
+
+void AnalogPotentiometer::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", Get());
+  }
+}
+
+std::shared_ptr<ITable> AnalogPotentiometer::GetTable() const {
+  return m_table;
+}
diff --git a/wpilibc/athena/src/AnalogTrigger.cpp b/wpilibc/athena/src/AnalogTrigger.cpp
new file mode 100644
index 0000000..220c897
--- /dev/null
+++ b/wpilibc/athena/src/AnalogTrigger.cpp
@@ -0,0 +1,185 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "AnalogTrigger.h"
+
+#include <memory>
+
+#include "AnalogInput.h"
+#include "HAL/HAL.h"
+#include "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/wpilibc/athena/src/AnalogTriggerOutput.cpp b/wpilibc/athena/src/AnalogTriggerOutput.cpp
new file mode 100644
index 0000000..e43f5ba
--- /dev/null
+++ b/wpilibc/athena/src/AnalogTriggerOutput.cpp
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "AnalogTriggerOutput.h"
+
+#include "AnalogTrigger.h"
+#include "HAL/HAL.h"
+#include "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/wpilibc/athena/src/BuiltInAccelerometer.cpp b/wpilibc/athena/src/BuiltInAccelerometer.cpp
new file mode 100644
index 0000000..8b80bca
--- /dev/null
+++ b/wpilibc/athena/src/BuiltInAccelerometer.cpp
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "BuiltInAccelerometer.h"
+
+#include "HAL/Accelerometer.h"
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Constructor.
+ *
+ * @param range The range the accelerometer will measure
+ */
+BuiltInAccelerometer::BuiltInAccelerometer(Range range) {
+  SetRange(range);
+
+  HAL_Report(HALUsageReporting::kResourceType_Accelerometer, 0, 0,
+             "Built-in accelerometer");
+  LiveWindow::GetInstance()->AddSensor((std::string) "BuiltInAccel", 0, this);
+}
+
+void BuiltInAccelerometer::SetRange(Range range) {
+  if (range == kRange_16G) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange, "16G range not supported (use k2G, k4G, or k8G)");
+  }
+
+  HAL_SetAccelerometerActive(false);
+  HAL_SetAccelerometerRange((HAL_AccelerometerRange)range);
+  HAL_SetAccelerometerActive(true);
+}
+
+/**
+ * @return The acceleration of the roboRIO along the X axis in g-forces
+ */
+double BuiltInAccelerometer::GetX() { return HAL_GetAccelerometerX(); }
+
+/**
+ * @return The acceleration of the roboRIO along the Y axis in g-forces
+ */
+double BuiltInAccelerometer::GetY() { return HAL_GetAccelerometerY(); }
+
+/**
+ * @return The acceleration of the roboRIO along the Z axis in g-forces
+ */
+double BuiltInAccelerometer::GetZ() { return HAL_GetAccelerometerZ(); }
+
+std::string BuiltInAccelerometer::GetSmartDashboardType() const {
+  return "3AxisAccelerometer";
+}
+
+void BuiltInAccelerometer::InitTable(std::shared_ptr<ITable> subtable) {
+  m_table = subtable;
+  UpdateTable();
+}
+
+void BuiltInAccelerometer::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("X", GetX());
+    m_table->PutNumber("Y", GetY());
+    m_table->PutNumber("Z", GetZ());
+  }
+}
+
+std::shared_ptr<ITable> BuiltInAccelerometer::GetTable() const {
+  return m_table;
+}
diff --git a/wpilibc/athena/src/CameraServer.cpp b/wpilibc/athena/src/CameraServer.cpp
new file mode 100644
index 0000000..8492133
--- /dev/null
+++ b/wpilibc/athena/src/CameraServer.cpp
@@ -0,0 +1,712 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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 "CameraServer.h"
+
+#include "Utility.h"
+#include "WPIErrors.h"
+#include "llvm/SmallString.h"
+#include "llvm/raw_ostream.h"
+#include "ntcore_cpp.h"
+
+using namespace frc;
+
+CameraServer* CameraServer::GetInstance() {
+  static CameraServer instance;
+  return &instance;
+}
+
+static llvm::StringRef MakeSourceValue(CS_Source source,
+                                       llvm::SmallVectorImpl<char>& buf) {
+  CS_Status status = 0;
+  buf.clear();
+  switch (cs::GetSourceKind(source, &status)) {
+    case cs::VideoSource::kUsb: {
+      llvm::StringRef prefix{"usb:"};
+      buf.append(prefix.begin(), prefix.end());
+      auto path = cs::GetUsbCameraPath(source, &status);
+      buf.append(path.begin(), path.end());
+      break;
+    }
+    case cs::VideoSource::kHttp: {
+      llvm::StringRef prefix{"ip:"};
+      buf.append(prefix.begin(), prefix.end());
+      auto urls = cs::GetHttpCameraUrls(source, &status);
+      if (!urls.empty()) buf.append(urls[0].begin(), urls[0].end());
+      break;
+    }
+    case cs::VideoSource::kCv:
+      // FIXME: Should be "cv:", but LabVIEW dashboard requires "usb:".
+      // https://github.com/wpilibsuite/allwpilib/issues/407
+      return "usb:";
+    default:
+      return "unknown:";
+  }
+
+  return llvm::StringRef{buf.begin(), buf.size()};
+}
+
+static std::string MakeStreamValue(llvm::StringRef address, int port) {
+  std::string rv;
+  llvm::raw_string_ostream stream(rv);
+  stream << "mjpg:http://" << address << ':' << port << "/?action=stream";
+  stream.flush();
+  return rv;
+}
+
+std::shared_ptr<ITable> CameraServer::GetSourceTable(CS_Source source) {
+  std::lock_guard<std::mutex> lock(m_mutex);
+  return m_tables.lookup(source);
+}
+
+std::vector<std::string> CameraServer::GetSinkStreamValues(CS_Sink sink) {
+  CS_Status status = 0;
+
+  // Ignore all but MjpegServer
+  if (cs::GetSinkKind(sink, &status) != CS_SINK_MJPEG)
+    return std::vector<std::string>{};
+
+  // Get port
+  int port = cs::GetMjpegServerPort(sink, &status);
+
+  // Generate values
+  std::vector<std::string> values;
+  auto listenAddress = cs::GetMjpegServerListenAddress(sink, &status);
+  if (!listenAddress.empty()) {
+    // If a listen address is specified, only use that
+    values.emplace_back(MakeStreamValue(listenAddress, port));
+  } else {
+    // Otherwise generate for hostname and all interface addresses
+    values.emplace_back(MakeStreamValue(cs::GetHostname() + ".local", port));
+
+    for (const auto& addr : m_addresses) {
+      if (addr == "127.0.0.1") continue;  // ignore localhost
+      values.emplace_back(MakeStreamValue(addr, port));
+    }
+  }
+
+  return values;
+}
+
+std::vector<std::string> CameraServer::GetSourceStreamValues(CS_Source source) {
+  CS_Status status = 0;
+
+  // Ignore all but HttpCamera
+  if (cs::GetSourceKind(source, &status) != CS_SOURCE_HTTP)
+    return std::vector<std::string>{};
+
+  // Generate values
+  auto values = cs::GetHttpCameraUrls(source, &status);
+  for (auto& value : values) value = "mjpg:" + value;
+
+  // Look to see if we have a passthrough server for this source
+  for (const auto& i : m_sinks) {
+    CS_Sink sink = i.second.GetHandle();
+    CS_Source sinkSource = cs::GetSinkSource(sink, &status);
+    if (source == sinkSource &&
+        cs::GetSinkKind(sink, &status) == CS_SINK_MJPEG) {
+      // Add USB-only passthrough
+      int port = cs::GetMjpegServerPort(sink, &status);
+      values.emplace_back(MakeStreamValue("172.22.11.2", port));
+      break;
+    }
+  }
+
+  // Set table value
+  return values;
+}
+
+void CameraServer::UpdateStreamValues() {
+  std::lock_guard<std::mutex> lock(m_mutex);
+  // Over all the sinks...
+  for (const auto& i : m_sinks) {
+    CS_Status status = 0;
+    CS_Sink sink = i.second.GetHandle();
+
+    // Get the source's subtable (if none exists, we're done)
+    CS_Source source = cs::GetSinkSource(sink, &status);
+    if (source == 0) continue;
+    auto table = m_tables.lookup(source);
+    if (table) {
+      // Don't set stream values if this is a HttpCamera passthrough
+      if (cs::GetSourceKind(source, &status) == CS_SOURCE_HTTP) continue;
+
+      // Set table value
+      auto values = GetSinkStreamValues(sink);
+      if (!values.empty()) table->PutStringArray("streams", values);
+    }
+  }
+
+  // Over all the sources...
+  for (const auto& i : m_sources) {
+    CS_Source source = i.second.GetHandle();
+
+    // Get the source's subtable (if none exists, we're done)
+    auto table = m_tables.lookup(source);
+    if (table) {
+      // Set table value
+      auto values = GetSourceStreamValues(source);
+      if (!values.empty()) table->PutStringArray("streams", values);
+    }
+  }
+}
+
+static std::string PixelFormatToString(int pixelFormat) {
+  switch (pixelFormat) {
+    case cs::VideoMode::PixelFormat::kMJPEG:
+      return "MJPEG";
+    case cs::VideoMode::PixelFormat::kYUYV:
+      return "YUYV";
+    case cs::VideoMode::PixelFormat::kRGB565:
+      return "RGB565";
+    case cs::VideoMode::PixelFormat::kBGR:
+      return "BGR";
+    case cs::VideoMode::PixelFormat::kGray:
+      return "Gray";
+    default:
+      return "Unknown";
+  }
+}
+#if 0
+static cs::VideoMode::PixelFormat PixelFormatFromString(llvm::StringRef str) {
+  if (str == "MJPEG" || str == "mjpeg" || str == "JPEG" || str == "jpeg")
+    return cs::VideoMode::PixelFormat::kMJPEG;
+  if (str == "YUYV" || str == "yuyv") return cs::VideoMode::PixelFormat::kYUYV;
+  if (str == "RGB565" || str == "rgb565")
+    return cs::VideoMode::PixelFormat::kRGB565;
+  if (str == "BGR" || str == "bgr") return cs::VideoMode::PixelFormat::kBGR;
+  if (str == "GRAY" || str == "Gray" || str == "gray")
+    return cs::VideoMode::PixelFormat::kGray;
+  return cs::VideoMode::PixelFormat::kUnknown;
+}
+
+static cs::VideoMode VideoModeFromString(llvm::StringRef modeStr) {
+  cs::VideoMode mode;
+  size_t pos;
+
+  // width: [0-9]+
+  pos = modeStr.find_first_not_of("0123456789");
+  llvm::StringRef widthStr = modeStr.slice(0, pos);
+  modeStr = modeStr.drop_front(pos).ltrim();  // drop whitespace too
+
+  // 'x'
+  if (modeStr.empty() || modeStr[0] != 'x') return mode;
+  modeStr = modeStr.drop_front(1).ltrim();  // drop whitespace too
+
+  // height: [0-9]+
+  pos = modeStr.find_first_not_of("0123456789");
+  llvm::StringRef heightStr = modeStr.slice(0, pos);
+  modeStr = modeStr.drop_front(pos).ltrim();  // drop whitespace too
+
+  // format: all characters until whitespace
+  pos = modeStr.find_first_of(" \t\n\v\f\r");
+  llvm::StringRef formatStr = modeStr.slice(0, pos);
+  modeStr = modeStr.drop_front(pos).ltrim();  // drop whitespace too
+
+  // fps: [0-9.]+
+  pos = modeStr.find_first_not_of("0123456789.");
+  llvm::StringRef fpsStr = modeStr.slice(0, pos);
+  modeStr = modeStr.drop_front(pos).ltrim();  // drop whitespace too
+
+  // "fps"
+  if (!modeStr.startswith("fps")) return mode;
+
+  // make fps an integer string by dropping after the decimal
+  fpsStr = fpsStr.slice(0, fpsStr.find('.'));
+
+  // convert width, height, and fps to integers
+  if (widthStr.getAsInteger(10, mode.width)) return mode;
+  if (heightStr.getAsInteger(10, mode.height)) return mode;
+  if (fpsStr.getAsInteger(10, mode.fps)) return mode;
+
+  // convert format to enum value
+  mode.pixelFormat = PixelFormatFromString(formatStr);
+
+  return mode;
+}
+#endif
+static std::string VideoModeToString(const cs::VideoMode& mode) {
+  std::string rv;
+  llvm::raw_string_ostream oss{rv};
+  oss << mode.width << "x" << mode.height;
+  oss << " " << PixelFormatToString(mode.pixelFormat) << " ";
+  oss << mode.fps << " fps";
+  return oss.str();
+}
+
+static std::vector<std::string> GetSourceModeValues(int source) {
+  std::vector<std::string> rv;
+  CS_Status status = 0;
+  for (const auto& mode : cs::EnumerateSourceVideoModes(source, &status))
+    rv.emplace_back(VideoModeToString(mode));
+  return rv;
+}
+
+static inline llvm::StringRef Concatenate(llvm::StringRef lhs,
+                                          llvm::StringRef rhs,
+                                          llvm::SmallVectorImpl<char>& buf) {
+  buf.clear();
+  llvm::raw_svector_ostream oss{buf};
+  oss << lhs << rhs;
+  return oss.str();
+}
+
+static void PutSourcePropertyValue(ITable* table, const cs::VideoEvent& event,
+                                   bool isNew) {
+  llvm::SmallString<64> name;
+  llvm::SmallString<64> infoName;
+  if (llvm::StringRef{event.name}.startswith("raw_")) {
+    name = "RawProperty/";
+    name += event.name;
+    infoName = "RawPropertyInfo/";
+    infoName += event.name;
+  } else {
+    name = "Property/";
+    name += event.name;
+    infoName = "PropertyInfo/";
+    infoName += event.name;
+  }
+
+  llvm::SmallString<64> buf;
+  CS_Status status = 0;
+  switch (event.propertyKind) {
+    case cs::VideoProperty::kBoolean:
+      if (isNew)
+        table->SetDefaultBoolean(name, event.value != 0);
+      else
+        table->PutBoolean(name, event.value != 0);
+      break;
+    case cs::VideoProperty::kInteger:
+    case cs::VideoProperty::kEnum:
+      if (isNew) {
+        table->SetDefaultNumber(name, event.value);
+        table->PutNumber(Concatenate(infoName, "/min", buf),
+                         cs::GetPropertyMin(event.propertyHandle, &status));
+        table->PutNumber(Concatenate(infoName, "/max", buf),
+                         cs::GetPropertyMax(event.propertyHandle, &status));
+        table->PutNumber(Concatenate(infoName, "/step", buf),
+                         cs::GetPropertyStep(event.propertyHandle, &status));
+        table->PutNumber(Concatenate(infoName, "/default", buf),
+                         cs::GetPropertyDefault(event.propertyHandle, &status));
+      } else {
+        table->PutNumber(name, event.value);
+      }
+      break;
+    case cs::VideoProperty::kString:
+      if (isNew)
+        table->SetDefaultString(name, event.valueStr);
+      else
+        table->PutString(name, event.valueStr);
+      break;
+    default:
+      break;
+  }
+}
+
+CameraServer::CameraServer()
+    : m_publishTable{NetworkTable::GetTable(kPublishName)},
+      m_nextPort(kBasePort) {
+  // We publish sources to NetworkTables using the following structure:
+  // "/CameraPublisher/{Source.Name}/" - root
+  // - "source" (string): Descriptive, prefixed with type (e.g. "usb:0")
+  // - "streams" (string array): URLs that can be used to stream data
+  // - "description" (string): Description of the source
+  // - "connected" (boolean): Whether source is connected
+  // - "mode" (string): Current video mode
+  // - "modes" (string array): Available video modes
+  // - "Property/{Property}" - Property values
+  // - "PropertyInfo/{Property}" - Property supporting information
+
+  // Listener for video events
+  m_videoListener = cs::VideoListener{
+      [=](const cs::VideoEvent& event) {
+        CS_Status status = 0;
+        switch (event.kind) {
+          case cs::VideoEvent::kSourceCreated: {
+            // Create subtable for the camera
+            auto table = m_publishTable->GetSubTable(event.name);
+            {
+              std::lock_guard<std::mutex> lock(m_mutex);
+              m_tables.insert(std::make_pair(event.sourceHandle, table));
+            }
+            llvm::SmallString<64> buf;
+            table->PutString("source",
+                             MakeSourceValue(event.sourceHandle, buf));
+            llvm::SmallString<64> descBuf;
+            table->PutString(
+                "description",
+                cs::GetSourceDescription(event.sourceHandle, descBuf, &status));
+            table->PutBoolean("connected", cs::IsSourceConnected(
+                                               event.sourceHandle, &status));
+            table->PutStringArray("streams",
+                                  GetSourceStreamValues(event.sourceHandle));
+            auto mode = cs::GetSourceVideoMode(event.sourceHandle, &status);
+            table->SetDefaultString("mode", VideoModeToString(mode));
+            table->PutStringArray("modes",
+                                  GetSourceModeValues(event.sourceHandle));
+            break;
+          }
+          case cs::VideoEvent::kSourceDestroyed: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table) {
+              table->PutString("source", "");
+              table->PutStringArray("streams", std::vector<std::string>{});
+              table->PutStringArray("modes", std::vector<std::string>{});
+            }
+            break;
+          }
+          case cs::VideoEvent::kSourceConnected: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table) {
+              // update the description too (as it may have changed)
+              llvm::SmallString<64> descBuf;
+              table->PutString("description",
+                               cs::GetSourceDescription(event.sourceHandle,
+                                                        descBuf, &status));
+              table->PutBoolean("connected", true);
+            }
+            break;
+          }
+          case cs::VideoEvent::kSourceDisconnected: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table) table->PutBoolean("connected", false);
+            break;
+          }
+          case cs::VideoEvent::kSourceVideoModesUpdated: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table)
+              table->PutStringArray("modes",
+                                    GetSourceModeValues(event.sourceHandle));
+            break;
+          }
+          case cs::VideoEvent::kSourceVideoModeChanged: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table) table->PutString("mode", VideoModeToString(event.mode));
+            break;
+          }
+          case cs::VideoEvent::kSourcePropertyCreated: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table) PutSourcePropertyValue(table.get(), event, true);
+            break;
+          }
+          case cs::VideoEvent::kSourcePropertyValueUpdated: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table) PutSourcePropertyValue(table.get(), event, false);
+            break;
+          }
+          case cs::VideoEvent::kSourcePropertyChoicesUpdated: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table) {
+              llvm::SmallString<64> name{"PropertyInfo/"};
+              name += event.name;
+              name += "/choices";
+              auto choices =
+                  cs::GetEnumPropertyChoices(event.propertyHandle, &status);
+              table->PutStringArray(name, choices);
+            }
+            break;
+          }
+          case cs::VideoEvent::kSinkSourceChanged:
+          case cs::VideoEvent::kSinkCreated:
+          case cs::VideoEvent::kSinkDestroyed: {
+            UpdateStreamValues();
+            break;
+          }
+          case cs::VideoEvent::kNetworkInterfacesChanged: {
+            m_addresses = cs::GetNetworkInterfaces();
+            break;
+          }
+          default:
+            break;
+        }
+      },
+      0x4fff, true};
+
+  // Listener for NetworkTable events
+  // We don't currently support changing settings via NT due to
+  // synchronization issues, so just update to current setting if someone
+  // else tries to change it.
+  llvm::SmallString<64> buf;
+  m_tableListener = nt::AddEntryListener(
+      Concatenate(kPublishName, "/", buf),
+      [=](unsigned int uid, llvm::StringRef key,
+          std::shared_ptr<nt::Value> value, unsigned int flags) {
+        llvm::StringRef relativeKey =
+            key.substr(llvm::StringRef(kPublishName).size() + 1);
+
+        // get source (sourceName/...)
+        auto subKeyIndex = relativeKey.find('/');
+        if (subKeyIndex == llvm::StringRef::npos) return;
+        llvm::StringRef sourceName = relativeKey.slice(0, subKeyIndex);
+        auto sourceIt = m_sources.find(sourceName);
+        if (sourceIt == m_sources.end()) return;
+
+        // get subkey
+        relativeKey = relativeKey.substr(subKeyIndex + 1);
+
+        // handle standard names
+        llvm::StringRef propName;
+        if (relativeKey == "mode") {
+          // reset to current mode
+          nt::SetEntryValue(key, nt::Value::MakeString(VideoModeToString(
+                                     sourceIt->second.GetVideoMode())));
+          return;
+        } else if (relativeKey.startswith("Property/")) {
+          propName = relativeKey.substr(9);
+        } else if (relativeKey.startswith("RawProperty/")) {
+          propName = relativeKey.substr(12);
+        } else {
+          return;  // ignore
+        }
+
+        // everything else is a property
+        auto property = sourceIt->second.GetProperty(propName);
+        switch (property.GetKind()) {
+          case cs::VideoProperty::kNone:
+            return;
+          case cs::VideoProperty::kBoolean:
+            nt::SetEntryValue(key, nt::Value::MakeBoolean(property.Get() != 0));
+            return;
+          case cs::VideoProperty::kInteger:
+          case cs::VideoProperty::kEnum:
+            nt::SetEntryValue(key, nt::Value::MakeDouble(property.Get()));
+            return;
+          case cs::VideoProperty::kString:
+            nt::SetEntryValue(key, nt::Value::MakeString(property.GetString()));
+            return;
+          default:
+            return;
+        }
+      },
+      NT_NOTIFY_IMMEDIATE | NT_NOTIFY_UPDATE);
+}
+
+cs::UsbCamera CameraServer::StartAutomaticCapture() {
+  return StartAutomaticCapture(m_defaultUsbDevice++);
+}
+
+cs::UsbCamera CameraServer::StartAutomaticCapture(int dev) {
+  llvm::SmallString<64> buf;
+  llvm::raw_svector_ostream name{buf};
+  name << "USB Camera " << dev;
+
+  cs::UsbCamera camera{name.str(), dev};
+  StartAutomaticCapture(camera);
+  return camera;
+}
+
+cs::UsbCamera CameraServer::StartAutomaticCapture(llvm::StringRef name,
+                                                  int dev) {
+  cs::UsbCamera camera{name, dev};
+  StartAutomaticCapture(camera);
+  return camera;
+}
+
+cs::UsbCamera CameraServer::StartAutomaticCapture(llvm::StringRef name,
+                                                  llvm::StringRef path) {
+  cs::UsbCamera camera{name, path};
+  StartAutomaticCapture(camera);
+  return camera;
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(llvm::StringRef host) {
+  return AddAxisCamera("Axis Camera", host);
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(const char* host) {
+  return AddAxisCamera("Axis Camera", host);
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(const std::string& host) {
+  return AddAxisCamera("Axis Camera", host);
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(llvm::ArrayRef<std::string> hosts) {
+  return AddAxisCamera("Axis Camera", hosts);
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(llvm::StringRef name,
+                                           llvm::StringRef host) {
+  cs::AxisCamera camera{name, host};
+  StartAutomaticCapture(camera);
+  return camera;
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(llvm::StringRef name,
+                                           const char* host) {
+  cs::AxisCamera camera{name, host};
+  StartAutomaticCapture(camera);
+  return camera;
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(llvm::StringRef name,
+                                           const std::string& host) {
+  cs::AxisCamera camera{name, host};
+  StartAutomaticCapture(camera);
+  return camera;
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(llvm::StringRef name,
+                                           llvm::ArrayRef<std::string> hosts) {
+  cs::AxisCamera camera{name, hosts};
+  StartAutomaticCapture(camera);
+  return camera;
+}
+
+void CameraServer::StartAutomaticCapture(const cs::VideoSource& camera) {
+  llvm::SmallString<64> name{"serve_"};
+  name += camera.GetName();
+
+  AddCamera(camera);
+  auto server = AddServer(name);
+  server.SetSource(camera);
+}
+
+cs::CvSink CameraServer::GetVideo() {
+  cs::VideoSource source;
+  {
+    std::lock_guard<std::mutex> lock(m_mutex);
+    if (m_primarySourceName.empty()) {
+      wpi_setWPIErrorWithContext(CameraServerError, "no camera available");
+      return cs::CvSink{};
+    }
+    auto it = m_sources.find(m_primarySourceName);
+    if (it == m_sources.end()) {
+      wpi_setWPIErrorWithContext(CameraServerError, "no camera available");
+      return cs::CvSink{};
+    }
+    source = it->second;
+  }
+  return GetVideo(std::move(source));
+}
+
+cs::CvSink CameraServer::GetVideo(const cs::VideoSource& camera) {
+  llvm::SmallString<64> name{"opencv_"};
+  name += camera.GetName();
+
+  {
+    std::lock_guard<std::mutex> lock(m_mutex);
+    auto it = m_sinks.find(name);
+    if (it != m_sinks.end()) {
+      auto kind = it->second.GetKind();
+      if (kind != cs::VideoSink::kCv) {
+        llvm::SmallString<64> buf;
+        llvm::raw_svector_ostream err{buf};
+        err << "expected OpenCV sink, but got " << kind;
+        wpi_setWPIErrorWithContext(CameraServerError, err.str());
+        return cs::CvSink{};
+      }
+      return *static_cast<cs::CvSink*>(&it->second);
+    }
+  }
+
+  cs::CvSink newsink{name};
+  newsink.SetSource(camera);
+  AddServer(newsink);
+  return newsink;
+}
+
+cs::CvSink CameraServer::GetVideo(llvm::StringRef name) {
+  cs::VideoSource source;
+  {
+    std::lock_guard<std::mutex> lock(m_mutex);
+    auto it = m_sources.find(name);
+    if (it == m_sources.end()) {
+      llvm::SmallString<64> buf;
+      llvm::raw_svector_ostream err{buf};
+      err << "could not find camera " << name;
+      wpi_setWPIErrorWithContext(CameraServerError, err.str());
+      return cs::CvSink{};
+    }
+    source = it->second;
+  }
+  return GetVideo(source);
+}
+
+cs::CvSource CameraServer::PutVideo(llvm::StringRef name, int width,
+                                    int height) {
+  cs::CvSource source{name, cs::VideoMode::kMJPEG, width, height, 30};
+  StartAutomaticCapture(source);
+  return source;
+}
+
+cs::MjpegServer CameraServer::AddServer(llvm::StringRef name) {
+  int port;
+  {
+    std::lock_guard<std::mutex> lock(m_mutex);
+    port = m_nextPort++;
+  }
+  return AddServer(name, port);
+}
+
+cs::MjpegServer CameraServer::AddServer(llvm::StringRef name, int port) {
+  cs::MjpegServer server{name, port};
+  AddServer(server);
+  return server;
+}
+
+void CameraServer::AddServer(const cs::VideoSink& server) {
+  std::lock_guard<std::mutex> lock(m_mutex);
+  m_sinks.emplace_second(server.GetName(), server);
+}
+
+void CameraServer::RemoveServer(llvm::StringRef name) {
+  std::lock_guard<std::mutex> lock(m_mutex);
+  m_sinks.erase(name);
+}
+
+cs::VideoSink CameraServer::GetServer() {
+  llvm::SmallString<64> name;
+  {
+    std::lock_guard<std::mutex> lock(m_mutex);
+    if (m_primarySourceName.empty()) {
+      wpi_setWPIErrorWithContext(CameraServerError, "no camera available");
+      return cs::VideoSink{};
+    }
+    name = "serve_";
+    name += m_primarySourceName;
+  }
+  return GetServer(name);
+}
+
+cs::VideoSink CameraServer::GetServer(llvm::StringRef name) {
+  std::lock_guard<std::mutex> lock(m_mutex);
+  auto it = m_sinks.find(name);
+  if (it == m_sinks.end()) {
+    llvm::SmallString<64> buf;
+    llvm::raw_svector_ostream err{buf};
+    err << "could not find server " << name;
+    wpi_setWPIErrorWithContext(CameraServerError, err.str());
+    return cs::VideoSink{};
+  }
+  return it->second;
+}
+
+void CameraServer::AddCamera(const cs::VideoSource& camera) {
+  std::string name = camera.GetName();
+  std::lock_guard<std::mutex> lock(m_mutex);
+  if (m_primarySourceName.empty()) m_primarySourceName = name;
+  m_sources.emplace_second(name, camera);
+}
+
+void CameraServer::RemoveCamera(llvm::StringRef name) {
+  std::lock_guard<std::mutex> lock(m_mutex);
+  m_sources.erase(name);
+}
+
+void CameraServer::SetSize(int size) {
+  std::lock_guard<std::mutex> lock(m_mutex);
+  if (m_primarySourceName.empty()) return;
+  auto it = m_sources.find(m_primarySourceName);
+  if (it == m_sources.end()) return;
+  if (size == kSize160x120)
+    it->second.SetResolution(160, 120);
+  else if (size == kSize320x240)
+    it->second.SetResolution(320, 240);
+  else if (size == kSize640x480)
+    it->second.SetResolution(640, 480);
+}
diff --git a/wpilibc/athena/src/Compressor.cpp b/wpilibc/athena/src/Compressor.cpp
new file mode 100644
index 0000000..84722c7
--- /dev/null
+++ b/wpilibc/athena/src/Compressor.cpp
@@ -0,0 +1,328 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Compressor.h"
+#include "HAL/Compressor.h"
+
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "HAL/Solenoid.h"
+#include "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);
+  }
+}
+
+void Compressor::UpdateTable() {
+  if (m_table) {
+    m_table->PutBoolean("Enabled", Enabled());
+    m_table->PutBoolean("Pressure switch", GetPressureSwitchValue());
+  }
+}
+
+void Compressor::StartLiveWindowMode() {}
+
+void Compressor::StopLiveWindowMode() {}
+
+std::string Compressor::GetSmartDashboardType() const { return "Compressor"; }
+
+void Compressor::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> Compressor::GetTable() const { return m_table; }
+
+void Compressor::ValueChanged(ITable* source, llvm::StringRef key,
+                              std::shared_ptr<nt::Value> value, bool isNew) {
+  if (!value->IsBoolean()) return;
+  if (value->GetBoolean())
+    Start();
+  else
+    Stop();
+}
diff --git a/wpilibc/athena/src/ControllerPower.cpp b/wpilibc/athena/src/ControllerPower.cpp
new file mode 100644
index 0000000..8694781
--- /dev/null
+++ b/wpilibc/athena/src/ControllerPower.cpp
@@ -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 "ControllerPower.h"
+
+#include <stdint.h>
+
+#include "ErrorBase.h"
+#include "HAL/HAL.h"
+#include "HAL/Power.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/wpilibc/athena/src/Counter.cpp b/wpilibc/athena/src/Counter.cpp
new file mode 100644
index 0000000..ca13452
--- /dev/null
+++ b/wpilibc/athena/src/Counter.cpp
@@ -0,0 +1,637 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Counter.h"
+
+#include "AnalogTrigger.h"
+#include "DigitalInput.h"
+#include "HAL/HAL.h"
+#include "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 pointer to the existing AnalogTrigger object.
+ */
+WPI_DEPRECATED("Use pass-by-reference instead.")
+Counter::Counter(AnalogTrigger* trigger) : Counter(kTwoPulse) {
+  SetUpSource(trigger->CreateOutput(AnalogTriggerType::kState));
+  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) {
+  if (StatusIsFatal()) return;
+  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) {
+  if (StatusIsFatal()) return;
+  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) {
+  if (StatusIsFatal()) return;
+  m_upSource = source;
+  if (m_upSource->StatusIsFatal()) {
+    CloneError(*m_upSource);
+  } else {
+    int32_t status = 0;
+    HAL_SetCounterUpSource(
+        m_counter, source->GetPortHandleForRouting(),
+        (HAL_AnalogTriggerType)source->GetAnalogTriggerTypeForRouting(),
+        &status);
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  }
+}
+
+void Counter::SetUpSource(DigitalSource* source) {
+  SetUpSource(
+      std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>()));
+}
+
+/**
+ * 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 (StatusIsFatal()) return;
+  if (m_upSource == nullptr) {
+    wpi_setWPIErrorWithContext(
+        NullParameter,
+        "Must set non-nullptr UpSource before setting UpSourceEdge");
+  }
+  int32_t status = 0;
+  HAL_SetCounterUpSourceEdge(m_counter, risingEdge, fallingEdge, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Disable the up counting source to the counter.
+ */
+void Counter::ClearUpSource() {
+  if (StatusIsFatal()) return;
+  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) {
+  if (StatusIsFatal()) return;
+  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) {
+  if (StatusIsFatal()) return;
+  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) {
+  if (StatusIsFatal()) return;
+  m_downSource = source;
+  if (m_downSource->StatusIsFatal()) {
+    CloneError(*m_downSource);
+  } else {
+    int32_t status = 0;
+    HAL_SetCounterDownSource(
+        m_counter, source->GetPortHandleForRouting(),
+        (HAL_AnalogTriggerType)source->GetAnalogTriggerTypeForRouting(),
+        &status);
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  }
+}
+
+void Counter::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 (StatusIsFatal()) return;
+  if (m_downSource == nullptr) {
+    wpi_setWPIErrorWithContext(
+        NullParameter,
+        "Must set non-nullptr DownSource before setting DownSourceEdge");
+  }
+  int32_t status = 0;
+  HAL_SetCounterDownSourceEdge(m_counter, risingEdge, fallingEdge, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Disable the down counting source to the counter.
+ */
+void Counter::ClearDownSource() {
+  if (StatusIsFatal()) return;
+  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() {
+  if (StatusIsFatal()) return;
+  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() {
+  if (StatusIsFatal()) return;
+  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) {
+  if (StatusIsFatal()) return;
+  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) {
+  if (StatusIsFatal()) return;
+  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 {
+  if (StatusIsFatal()) return 0;
+  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() {
+  if (StatusIsFatal()) return;
+  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 {
+  if (StatusIsFatal()) return 0.0;
+  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) {
+  if (StatusIsFatal()) return;
+  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) {
+  if (StatusIsFatal()) return;
+  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 {
+  if (StatusIsFatal()) return false;
+  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 {
+  if (StatusIsFatal()) return false;
+  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) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterReverseDirection(m_counter, reverseDirection, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Counter::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", Get());
+  }
+}
+
+void Counter::StartLiveWindowMode() {}
+
+void Counter::StopLiveWindowMode() {}
+
+std::string Counter::GetSmartDashboardType() const { return "Counter"; }
+
+void Counter::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> Counter::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/DigitalGlitchFilter.cpp b/wpilibc/athena/src/DigitalGlitchFilter.cpp
new file mode 100644
index 0000000..287ff88
--- /dev/null
+++ b/wpilibc/athena/src/DigitalGlitchFilter.cpp
@@ -0,0 +1,200 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DigitalGlitchFilter.h"
+
+#include <algorithm>
+#include <array>
+
+#include "Counter.h"
+#include "Encoder.h"
+#include "HAL/Constants.h"
+#include "HAL/DIO.h"
+#include "HAL/HAL.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+std::array<bool, 3> DigitalGlitchFilter::m_filterAllocated = {
+    {false, false, false}};
+priority_mutex DigitalGlitchFilter::m_mutex;
+
+DigitalGlitchFilter::DigitalGlitchFilter() {
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  auto index =
+      std::find(m_filterAllocated.begin(), m_filterAllocated.end(), false);
+  wpi_assert(index != m_filterAllocated.end());
+
+  m_channelIndex = std::distance(m_filterAllocated.begin(), index);
+  *index = true;
+
+  HAL_Report(HALUsageReporting::kResourceType_DigitalFilter, m_channelIndex);
+}
+
+DigitalGlitchFilter::~DigitalGlitchFilter() {
+  if (m_channelIndex >= 0) {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    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/wpilibc/athena/src/DigitalInput.cpp b/wpilibc/athena/src/DigitalInput.cpp
new file mode 100644
index 0000000..2eeefbb
--- /dev/null
+++ b/wpilibc/athena/src/DigitalInput.cpp
@@ -0,0 +1,122 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DigitalInput.h"
+
+#include <limits>
+#include <sstream>
+
+#include "HAL/DIO.h"
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "LiveWindow/LiveWindow.h"
+#include "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;
+  }
+
+  LiveWindow::GetInstance()->AddSensor("DigitalInput", channel, this);
+  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;
+}
+
+void DigitalInput::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutBoolean("Value", Get());
+  }
+}
+
+void DigitalInput::StartLiveWindowMode() {}
+
+void DigitalInput::StopLiveWindowMode() {}
+
+std::string DigitalInput::GetSmartDashboardType() const {
+  return "DigitalInput";
+}
+
+void DigitalInput::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> DigitalInput::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/DigitalOutput.cpp b/wpilibc/athena/src/DigitalOutput.cpp
new file mode 100644
index 0000000..381df60
--- /dev/null
+++ b/wpilibc/athena/src/DigitalOutput.cpp
@@ -0,0 +1,261 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DigitalOutput.h"
+
+#include <limits>
+#include <sstream>
+
+#include "HAL/DIO.h"
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "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 (m_table != nullptr) m_table->RemoveTableListener(this);
+  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;
+}
+
+void DigitalOutput::ValueChanged(ITable* source, llvm::StringRef key,
+                                 std::shared_ptr<nt::Value> value, bool isNew) {
+  if (!value->IsBoolean()) return;
+  Set(value->GetBoolean());
+}
+
+void DigitalOutput::UpdateTable() {}
+
+void DigitalOutput::StartLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->AddTableListener("Value", this, true);
+  }
+}
+
+void DigitalOutput::StopLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+std::string DigitalOutput::GetSmartDashboardType() const {
+  return "Digital Output";
+}
+
+void DigitalOutput::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> DigitalOutput::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/DoubleSolenoid.cpp b/wpilibc/athena/src/DoubleSolenoid.cpp
new file mode 100644
index 0000000..1954ada
--- /dev/null
+++ b/wpilibc/athena/src/DoubleSolenoid.cpp
@@ -0,0 +1,225 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DoubleSolenoid.h"
+
+#include <sstream>
+
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "HAL/Solenoid.h"
+#include "LiveWindow/LiveWindow.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Constructor.
+ *
+ * Uses the default PCM ID of 0.
+ *
+ * @param forwardChannel The forward channel number on the PCM (0..7).
+ * @param reverseChannel The reverse channel number on the PCM (0..7).
+ */
+DoubleSolenoid::DoubleSolenoid(int forwardChannel, int reverseChannel)
+    : DoubleSolenoid(GetDefaultSolenoidModule(), forwardChannel,
+                     reverseChannel) {}
+
+/**
+ * Constructor.
+ *
+ * @param moduleNumber   The CAN ID of the PCM.
+ * @param forwardChannel The forward channel on the PCM to control (0..7).
+ * @param reverseChannel The reverse channel on the PCM to control (0..7).
+ */
+DoubleSolenoid::DoubleSolenoid(int moduleNumber, int forwardChannel,
+                               int reverseChannel)
+    : SolenoidBase(moduleNumber),
+      m_forwardChannel(forwardChannel),
+      m_reverseChannel(reverseChannel) {
+  std::stringstream buf;
+  if (!CheckSolenoidModule(m_moduleNumber)) {
+    buf << "Solenoid Module " << m_moduleNumber;
+    wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf.str());
+    return;
+  }
+  if (!CheckSolenoidChannel(m_forwardChannel)) {
+    buf << "Solenoid Module " << m_forwardChannel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    return;
+  }
+  if (!CheckSolenoidChannel(m_reverseChannel)) {
+    buf << "Solenoid Module " << m_reverseChannel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    return;
+  }
+  int32_t status = 0;
+  m_forwardHandle = HAL_InitializeSolenoidPort(
+      HAL_GetPortWithModule(moduleNumber, m_forwardChannel), &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumSolenoidChannels(),
+                                 forwardChannel, HAL_GetErrorMessage(status));
+    m_forwardHandle = HAL_kInvalidHandle;
+    m_reverseHandle = HAL_kInvalidHandle;
+    return;
+  }
+
+  m_reverseHandle = HAL_InitializeSolenoidPort(
+      HAL_GetPortWithModule(moduleNumber, m_reverseChannel), &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumSolenoidChannels(),
+                                 reverseChannel, HAL_GetErrorMessage(status));
+    // free forward solenoid
+    HAL_FreeSolenoidPort(m_forwardHandle);
+    m_forwardHandle = HAL_kInvalidHandle;
+    m_reverseHandle = HAL_kInvalidHandle;
+    return;
+  }
+
+  m_forwardMask = 1 << m_forwardChannel;
+  m_reverseMask = 1 << m_reverseChannel;
+
+  HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_forwardChannel,
+             m_moduleNumber);
+  HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_reverseChannel,
+             m_moduleNumber);
+  LiveWindow::GetInstance()->AddActuator("DoubleSolenoid", m_moduleNumber,
+                                         m_forwardChannel, this);
+}
+
+/**
+ * Destructor.
+ */
+DoubleSolenoid::~DoubleSolenoid() {
+  HAL_FreeSolenoidPort(m_forwardHandle);
+  HAL_FreeSolenoidPort(m_reverseHandle);
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+}
+
+/**
+ * Set the value of a solenoid.
+ *
+ * @param value The value to set (Off, Forward or Reverse)
+ */
+void DoubleSolenoid::Set(Value value) {
+  if (StatusIsFatal()) return;
+
+  bool forward = false;
+  bool reverse = false;
+  switch (value) {
+    case kOff:
+      forward = false;
+      reverse = false;
+      break;
+    case kForward:
+      forward = true;
+      reverse = false;
+      break;
+    case kReverse:
+      forward = false;
+      reverse = true;
+      break;
+  }
+  int fstatus = 0;
+  HAL_SetSolenoid(m_forwardHandle, forward, &fstatus);
+  int rstatus = 0;
+  HAL_SetSolenoid(m_reverseHandle, reverse, &rstatus);
+
+  wpi_setErrorWithContext(fstatus, HAL_GetErrorMessage(fstatus));
+  wpi_setErrorWithContext(rstatus, HAL_GetErrorMessage(rstatus));
+}
+
+/**
+ * Read the current value of the solenoid.
+ *
+ * @return The current value of the solenoid.
+ */
+DoubleSolenoid::Value DoubleSolenoid::Get() const {
+  if (StatusIsFatal()) return kOff;
+  int fstatus = 0;
+  int rstatus = 0;
+  bool valueForward = HAL_GetSolenoid(m_forwardHandle, &fstatus);
+  bool valueReverse = HAL_GetSolenoid(m_reverseHandle, &rstatus);
+
+  wpi_setErrorWithContext(fstatus, HAL_GetErrorMessage(fstatus));
+  wpi_setErrorWithContext(rstatus, HAL_GetErrorMessage(rstatus));
+
+  if (valueForward) return kForward;
+  if (valueReverse) return kReverse;
+  return kOff;
+}
+/**
+ * Check if the forward solenoid is blacklisted.
+ *
+ * If a solenoid is shorted, it is added to the blacklist and
+ * disabled until power cycle, or until faults are cleared.
+ * @see ClearAllPCMStickyFaults()
+ *
+ * @return If solenoid is disabled due to short.
+ */
+bool DoubleSolenoid::IsFwdSolenoidBlackListed() const {
+  int blackList = GetPCMSolenoidBlackList(m_moduleNumber);
+  return (blackList & m_forwardMask) ? 1 : 0;
+}
+/**
+ * Check if the reverse solenoid is blacklisted.
+ *
+ * If a solenoid is shorted, it is added to the blacklist and
+ * disabled until power cycle, or until faults are cleared.
+ * @see ClearAllPCMStickyFaults()
+ *
+ * @return If solenoid is disabled due to short.
+ */
+bool DoubleSolenoid::IsRevSolenoidBlackListed() const {
+  int blackList = GetPCMSolenoidBlackList(m_moduleNumber);
+  return (blackList & m_reverseMask) ? 1 : 0;
+}
+
+void DoubleSolenoid::ValueChanged(ITable* source, llvm::StringRef key,
+                                  std::shared_ptr<nt::Value> value,
+                                  bool isNew) {
+  if (!value->IsString()) return;
+  Value lvalue = kOff;
+  if (value->GetString() == "Forward")
+    lvalue = kForward;
+  else if (value->GetString() == "Reverse")
+    lvalue = kReverse;
+  Set(lvalue);
+}
+
+void DoubleSolenoid::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutString(
+        "Value", (Get() == kForward ? "Forward"
+                                    : (Get() == kReverse ? "Reverse" : "Off")));
+  }
+}
+
+void DoubleSolenoid::StartLiveWindowMode() {
+  Set(kOff);
+  if (m_table != nullptr) {
+    m_table->AddTableListener("Value", this, true);
+  }
+}
+
+void DoubleSolenoid::StopLiveWindowMode() {
+  Set(kOff);
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+std::string DoubleSolenoid::GetSmartDashboardType() const {
+  return "Double Solenoid";
+}
+
+void DoubleSolenoid::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> DoubleSolenoid::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/DriverStation.cpp b/wpilibc/athena/src/DriverStation.cpp
new file mode 100644
index 0000000..fd91d95
--- /dev/null
+++ b/wpilibc/athena/src/DriverStation.cpp
@@ -0,0 +1,672 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DriverStation.h"
+
+#include <chrono>
+
+#include "AnalogInput.h"
+#include "FRC_NetworkCommunication/FRCComm.h"
+#include "HAL/HAL.h"
+#include "HAL/Power.h"
+#include "HAL/cpp/Log.h"
+#include "MotorSafetyHelper.h"
+#include "Timer.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+#include "llvm/SmallString.h"
+
+using namespace frc;
+
+const double JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL = 1.0;
+
+const int DriverStation::kJoystickPorts;
+
+DriverStation::~DriverStation() {
+  m_isRunning = false;
+  m_dsThread.join();
+}
+
+/**
+ * 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_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+  std::unique_lock<priority_mutex> lock(m_joystickDataMutex);
+  if (axis >= m_joystickAxes[stick].count) {
+    // Unlock early so error printing isn't locked.
+    m_joystickDataMutex.unlock();
+    lock.release();
+    if (axis >= HAL_kMaxJoystickAxes)
+      wpi_setWPIError(BadJoystickAxis);
+    else
+      ReportJoystickUnpluggedWarning(
+          "Joystick Axis missing, check if all controllers are plugged in");
+    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_setWPIError(BadJoystickIndex);
+    return -1;
+  }
+  std::unique_lock<priority_mutex> lock(m_joystickDataMutex);
+  if (pov >= m_joystickPOVs[stick].count) {
+    // Unlock early so error printing isn't locked.
+    lock.unlock();
+    if (pov >= HAL_kMaxJoystickPOVs)
+      wpi_setWPIError(BadJoystickAxis);
+    else
+      ReportJoystickUnpluggedWarning(
+          "Joystick POV missing, check if all controllers are plugged in");
+    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_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+  std::lock_guard<priority_mutex> lock(m_joystickDataMutex);
+  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_setWPIError(BadJoystickIndex);
+    return false;
+  }
+  if (button == 0) {
+    ReportJoystickUnpluggedError(
+        "ERROR: Button indexes begin at 1 in WPILib for C++ and Java");
+    return false;
+  }
+  std::unique_lock<priority_mutex> lock(m_joystickDataMutex);
+  if (button > m_joystickButtons[stick].count) {
+    // Unlock early so error printing isn't locked.
+    lock.unlock();
+    ReportJoystickUnpluggedWarning(
+        "Joystick Button missing, check if all controllers are "
+        "plugged in");
+    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_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+  std::lock_guard<priority_mutex> lock(m_joystickDataMutex);
+  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_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+  std::lock_guard<priority_mutex> lock(m_joystickDataMutex);
+  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_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+  std::lock_guard<priority_mutex> lock(m_joystickDataMutex);
+  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_setWPIError(BadJoystickIndex);
+    return false;
+  }
+  std::lock_guard<priority_mutex> lock(m_joystickDataMutex);
+  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_setWPIError(BadJoystickIndex);
+    return -1;
+  }
+  std::lock_guard<priority_mutex> lock(m_joystickDataMutex);
+  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_setWPIError(BadJoystickIndex);
+  }
+  std::lock_guard<priority_mutex> lock(m_joystickDataMutex);
+  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_setWPIError(BadJoystickIndex);
+    return -1;
+  }
+  std::lock_guard<priority_mutex> lock(m_joystickDataMutex);
+  return m_joystickDescriptor[stick].axisTypes[axis];
+}
+
+/**
+ * Check if the DS has enabled the robot.
+ *
+ * @return True if the robot is enabled and the DS is connected
+ */
+bool DriverStation::IsEnabled() const {
+  HAL_ControlWord controlWord;
+  UpdateControlWord(false, controlWord);
+  return controlWord.enabled && controlWord.dsAttached;
+}
+
+/**
+ * Check if the robot is disabled.
+ *
+ * @return True if the robot is explicitly disabled or the DS is not connected
+ */
+bool DriverStation::IsDisabled() const {
+  HAL_ControlWord controlWord;
+  UpdateControlWord(false, controlWord);
+  return !(controlWord.enabled && controlWord.dsAttached);
+}
+
+/**
+ * Check if the DS is commanding autonomous mode.
+ *
+ * @return True if the robot is being commanded to be in autonomous mode
+ */
+bool DriverStation::IsAutonomous() const {
+  HAL_ControlWord controlWord;
+  UpdateControlWord(false, controlWord);
+  return controlWord.autonomous;
+}
+
+/**
+ * Check if the DS is commanding teleop mode.
+ *
+ * @return True if the robot is being commanded to be in teleop mode
+ */
+bool DriverStation::IsOperatorControl() const {
+  HAL_ControlWord controlWord;
+  UpdateControlWord(false, controlWord);
+  return !(controlWord.autonomous || controlWord.test);
+}
+
+/**
+ * Check if the DS is commanding test mode.
+ *
+ * @return True if the robot is being commanded to be in test mode
+ */
+bool DriverStation::IsTest() const {
+  HAL_ControlWord controlWord;
+  UpdateControlWord(false, controlWord);
+  return controlWord.test;
+}
+
+/**
+ * Check if the DS is attached.
+ *
+ * @return True if the DS is connected to the robot
+ */
+bool DriverStation::IsDSAttached() const {
+  HAL_ControlWord controlWord;
+  UpdateControlWord(false, controlWord);
+  return controlWord.dsAttached;
+}
+
+/**
+ * Has a new control packet from the driver station arrived since the last time
+ * this function was called?
+ *
+ * Warning: If you call this function from more than one place at the same time,
+ * you will not get the intended behavior.
+ *
+ * @return True if the control data has been updated since the last call.
+ */
+bool DriverStation::IsNewControlData() const {
+  return m_newControlData.exchange(false);
+}
+
+/**
+ * Is the driver station attached to a Field Management System?
+ *
+ * @return True if the robot is competing on a field being controlled by a Field
+ *         Management System
+ */
+bool DriverStation::IsFMSAttached() const {
+  HAL_ControlWord controlWord;
+  UpdateControlWord(false, controlWord);
+  return controlWord.fmsAttached;
+}
+
+/**
+ * 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;
+  }
+}
+
+/**
+ * Wait until a new packet comes from the driver station.
+ *
+ * This blocks on a semaphore, so the waiting is efficient.
+ *
+ * This is a good way to delay processing until there is new driver station data
+ * to act on.
+ */
+void DriverStation::WaitForData() { WaitForData(0); }
+
+/**
+ * Wait until a new packet comes from the driver station, or wait for a timeout.
+ *
+ * If the timeout is less then or equal to 0, wait indefinitely.
+ *
+ * Timeout is in milliseconds
+ *
+ * This blocks on a semaphore, so the waiting is efficient.
+ *
+ * This is a good way to delay processing until there is new driver station data
+ * to act on.
+ *
+ * @param timeout Timeout time in seconds
+ *
+ * @return true if new data, otherwise false
+ */
+bool DriverStation::WaitForData(double timeout) {
+#if defined(_MSC_VER) && _MSC_VER < 1900
+  auto timeoutTime = std::chrono::steady_clock::now() +
+                     std::chrono::duration<int64_t, std::nano>(
+                         static_cast<int64_t>(timeout * 1e9));
+#else
+  auto timeoutTime =
+      std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
+#endif
+
+  std::unique_lock<priority_mutex> lock(m_waitForDataMutex);
+  while (!m_waitForDataPredicate) {
+    if (timeout > 0) {
+      auto timedOut = m_waitForDataCond.wait_until(lock, timeoutTime);
+      if (timedOut == std::cv_status::timeout) {
+        return false;
+      }
+    } else {
+      m_waitForDataCond.wait(lock);
+    }
+  }
+  m_waitForDataPredicate = false;
+  return true;
+}
+
+/**
+ * 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]);
+  }
+  // Force a control word update, to make sure the data is the newest.
+  HAL_ControlWord controlWord;
+  UpdateControlWord(true, controlWord);
+  // Obtain a write lock on the data, swap the cached data into the
+  // main data arrays
+  std::lock_guard<priority_mutex> lock(m_joystickDataMutex);
+  m_joystickAxes.swap(m_joystickAxesCache);
+  m_joystickPOVs.swap(m_joystickPOVsCache);
+  m_joystickButtons.swap(m_joystickButtonsCache);
+  m_joystickDescriptor.swap(m_joystickDescriptorCache);
+}
+
+/**
+ * DriverStation constructor.
+ *
+ * This is only called once the first time GetInstance() is called
+ */
+DriverStation::DriverStation() {
+  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';
+  }
+
+  m_dsThread = std::thread(&DriverStation::Run, this);
+}
+
+/**
+ * Reports errors related to unplugged joysticks
+ * Throttles the errors so that they don't overwhelm the DS
+ */
+void DriverStation::ReportJoystickUnpluggedError(llvm::StringRef message) {
+  double currentTime = Timer::GetFPGATimestamp();
+  if (currentTime > m_nextMessageTime) {
+    ReportError(message);
+    m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL;
+  }
+}
+
+/**
+ * Reports errors related to unplugged joysticks.
+ *
+ * Throttles the errors so that they don't overwhelm the DS.
+ */
+void DriverStation::ReportJoystickUnpluggedWarning(llvm::StringRef message) {
+  double currentTime = Timer::GetFPGATimestamp();
+  if (currentTime > m_nextMessageTime) {
+    ReportWarning(message);
+    m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL;
+  }
+}
+
+void DriverStation::Run() {
+  m_isRunning = true;
+  int period = 0;
+  while (m_isRunning) {
+    HAL_WaitForDSData();
+    GetData();
+    // notify IsNewControlData variables
+    m_newControlData = true;
+
+    // notify WaitForData block
+    {
+      std::lock_guard<priority_mutex> lock(m_waitForDataMutex);
+      m_waitForDataPredicate = true;
+    }
+    m_waitForDataCond.notify_all();
+
+    if (++period >= 4) {
+      MotorSafetyHelper::CheckMotors();
+      period = 0;
+    }
+    if (m_userInDisabled) HAL_ObserveUserProgramDisabled();
+    if (m_userInAutonomous) HAL_ObserveUserProgramAutonomous();
+    if (m_userInTeleop) HAL_ObserveUserProgramTeleop();
+    if (m_userInTest) HAL_ObserveUserProgramTest();
+  }
+}
+
+/**
+ * Gets ControlWord data from the cache. If 50ms has passed, or the force
+ * parameter is set, the cached data is updated. Otherwise the data is just
+ * copied from the cache.
+ *
+ * @param force True to force an update to the cache, otherwise update if 50ms
+ * have passed.
+ * @param controlWord Structure to put the return control word data into.
+ */
+void DriverStation::UpdateControlWord(bool force,
+                                      HAL_ControlWord& controlWord) const {
+  auto now = std::chrono::steady_clock::now();
+  std::lock_guard<priority_mutex> lock(m_controlWordMutex);
+  // Update every 50 ms or on force.
+  if ((now - m_lastControlWordUpdate > std::chrono::milliseconds(50)) ||
+      force) {
+    HAL_GetControlWord(&m_controlWordCache);
+    m_lastControlWordUpdate = now;
+  }
+  controlWord = m_controlWordCache;
+}
diff --git a/wpilibc/athena/src/Encoder.cpp b/wpilibc/athena/src/Encoder.cpp
new file mode 100644
index 0000000..7fad9eb
--- /dev/null
+++ b/wpilibc/athena/src/Encoder.cpp
@@ -0,0 +1,527 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Encoder.h"
+
+#include "DigitalInput.h"
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * 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);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  HAL_Report(HALUsageReporting::kResourceType_Encoder, GetFPGAIndex(),
+             encodingType);
+  LiveWindow::GetInstance()->AddSensor("Encoder", m_aSource->GetChannel(),
+                                       this);
+}
+
+/**
+ * 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);
+}
+
+/**
+ * Encoder constructor.
+ *
+ * Construct a Encoder given a and b channels as digital inputs. This is used in
+ * the case where the digital inputs are shared. The Encoder class will not
+ * allocate the digital inputs and assume that they already are counted.
+ *
+ * The counter will start counting immediately.
+ *
+ * @param aSource          The source that should be used for the a channel.
+ * @param bSource          the source that should be used for the b channel.
+ * @param reverseDirection represents the orientation of the encoder and
+ *                         inverts the output values if necessary so forward
+ *                         represents positive values.
+ * @param encodingType     either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+ *                         decoding. If 4X is selected, then an encoder FPGA
+ *                         object is used and the returned counts will be 4x
+ *                         the encoder spec'd value since all rising and
+ *                         falling edges are counted. If 1X or 2X are selected
+ *                         then a counter object will be used and the returned
+ *                         value will either exactly match the spec'd count or
+ *                         be double (2x) the spec'd count.
+ */
+Encoder::Encoder(DigitalSource* aSource, DigitalSource* bSource,
+                 bool reverseDirection, EncodingType encodingType)
+    : m_aSource(aSource, NullDeleter<DigitalSource>()),
+      m_bSource(bSource, NullDeleter<DigitalSource>()) {
+  if (m_aSource == nullptr || m_bSource == nullptr)
+    wpi_setWPIError(NullParameter);
+  else
+    InitEncoder(reverseDirection, encodingType);
+}
+
+Encoder::Encoder(std::shared_ptr<DigitalSource> aSource,
+                 std::shared_ptr<DigitalSource> bSource, bool reverseDirection,
+                 EncodingType encodingType)
+    : m_aSource(aSource), m_bSource(bSource) {
+  if (m_aSource == nullptr || m_bSource == nullptr)
+    wpi_setWPIError(NullParameter);
+  else
+    InitEncoder(reverseDirection, encodingType);
+}
+
+/**
+ * Encoder constructor.
+ *
+ * Construct a Encoder given a and b channels as digital inputs. This is used in
+ * the case where the digital inputs are shared. The Encoder class will not
+ * allocate the digital inputs and assume that they already are counted.
+ *
+ * The counter will start counting immediately.
+ *
+ * @param aSource          The source that should be used for the a channel.
+ * @param bSource          the source that should be used for the b channel.
+ * @param reverseDirection represents the orientation of the encoder and
+ *                         inverts the output values if necessary so forward
+ *                         represents positive values.
+ * @param encodingType     either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+ *                         decoding. If 4X is selected, then an encoder FPGA
+ *                         object is used and the returned counts will be 4x
+ *                         the encoder spec'd value since all rising and
+ *                         falling edges are counted. If 1X or 2X are selected
+ *                         then a counter object will be used and the returned
+ *                         value will either exactly match the spec'd count or
+ *                         be double (2x) the spec'd count.
+ */
+Encoder::Encoder(DigitalSource& aSource, DigitalSource& bSource,
+                 bool reverseDirection, EncodingType encodingType)
+    : m_aSource(&aSource, NullDeleter<DigitalSource>()),
+      m_bSource(&bSource, NullDeleter<DigitalSource>()) {
+  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);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(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 {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetEncoderRaw(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Gets the current count.
+ *
+ * Returns the current count on the Encoder. This method compensates for the
+ * decoding type.
+ *
+ * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x scale
+ *         factor.
+ */
+int Encoder::Get() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetEncoder(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Reset the Encoder distance to zero.
+ *
+ * Resets the current count to zero on the encoder.
+ */
+void Encoder::Reset() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_ResetEncoder(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * 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 {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetEncoderPeriod(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(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) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetEncoderMaxPeriod(m_encoder, maxPeriod, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Determine if the encoder is stopped.
+ *
+ * Using the MaxPeriod value, a boolean is returned that is true if the encoder
+ * is considered stopped and false if it is still moving. A stopped encoder is
+ * one where the most recent pulse width exceeds the MaxPeriod.
+ *
+ * @return True if the encoder is considered stopped.
+ */
+bool Encoder::GetStopped() const {
+  if (StatusIsFatal()) return true;
+  int32_t status = 0;
+  bool value = HAL_GetEncoderStopped(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * The last direction the encoder value changed.
+ *
+ * @return The last direction the encoder value changed.
+ */
+bool Encoder::GetDirection() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = HAL_GetEncoderDirection(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * The scale needed to convert a raw counter value into a number of encoder
+ * pulses.
+ */
+double Encoder::DecodingScaleFactor() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double val = HAL_GetEncoderDecodingScaleFactor(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return val;
+}
+
+/**
+ * Get the distance the robot has driven since the last reset.
+ *
+ * @return The distance driven since the last reset as scaled by the value from
+ *         SetDistancePerPulse().
+ */
+double Encoder::GetDistance() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetEncoderDistance(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Get the current rate of the encoder.
+ *
+ * Units are distance per second as scaled by the value from
+ * SetDistancePerPulse().
+ *
+ * @return The current rate of the encoder.
+ */
+double Encoder::GetRate() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetEncoderRate(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Set the minimum rate of the device before the hardware reports it stopped.
+ *
+ * @param minRate The minimum rate.  The units are in distance per second as
+ *                scaled by the value from SetDistancePerPulse().
+ */
+void Encoder::SetMinRate(double minRate) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetEncoderMinRate(m_encoder, minRate, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Set the distance per pulse for this encoder.
+ *
+ * This sets the multiplier used to determine the distance driven based on the
+ * count value from the encoder.
+ *
+ * Do not include the decoding type in this scale.  The library already
+ * compensates for the decoding type.
+ *
+ * Set this value based on the encoder's rated Pulses per Revolution and
+ * factor in gearing reductions following the encoder shaft.
+ *
+ * This distance can be in any units you like, linear or angular.
+ *
+ * @param distancePerPulse The scale factor that will be used to convert pulses
+ *                         to useful units.
+ */
+void Encoder::SetDistancePerPulse(double distancePerPulse) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetEncoderDistancePerPulse(m_encoder, distancePerPulse, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Set the direction sensing for this encoder.
+ *
+ * This sets the direction sensing on the encoder so that it could count in the
+ * correct software direction regardless of the mounting.
+ *
+ * @param reverseDirection true if the encoder direction should be reversed
+ */
+void Encoder::SetReverseDirection(bool reverseDirection) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetEncoderReverseDirection(m_encoder, reverseDirection, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Set the Samples to Average which specifies the number of samples of the timer
+ * to average when calculating the period.
+ *
+ * Perform averaging to account for mechanical imperfections or as oversampling
+ * to increase resolution.
+ *
+ * @param samplesToAverage The number of samples to average from 1 to 127.
+ */
+void Encoder::SetSamplesToAverage(int samplesToAverage) {
+  if (samplesToAverage < 1 || samplesToAverage > 127) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange,
+        "Average counter values must be between 1 and 127");
+    return;
+  }
+  int32_t status = 0;
+  HAL_SetEncoderSamplesToAverage(m_encoder, samplesToAverage, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * 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 Encoder::GetSamplesToAverage() const {
+  int32_t status = 0;
+  int result = HAL_GetEncoderSamplesToAverage(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return result;
+}
+
+/**
+ * Implement the PIDSource interface.
+ *
+ * @return The current value of the selected source parameter.
+ */
+double Encoder::PIDGet() {
+  if (StatusIsFatal()) return 0.0;
+  switch (GetPIDSourceType()) {
+    case PIDSourceType::kDisplacement:
+      return GetDistance();
+    case PIDSourceType::kRate:
+      return GetRate();
+    default:
+      return 0.0;
+  }
+}
+
+/**
+ * Set the index source for the encoder.
+ *
+ * When this source is activated, the encoder count automatically resets.
+ *
+ * @param channel A DIO channel to set as the encoder index
+ * @param type    The state that will cause the encoder to reset
+ */
+void Encoder::SetIndexSource(int channel, Encoder::IndexingType type) {
+  // Force digital input if just given an index
+  m_indexSource = std::make_unique<DigitalInput>(channel);
+  SetIndexSource(m_indexSource.get(), type);
+}
+
+/**
+ * Set the index source for the encoder.
+ *
+ * When this source is activated, the encoder count automatically resets.
+ *
+ * @param channel A digital source to set as the encoder index
+ * @param type    The state that will cause the encoder to reset
+ */
+WPI_DEPRECATED("Use pass-by-reference instead.")
+void Encoder::SetIndexSource(DigitalSource* source,
+                             Encoder::IndexingType type) {
+  SetIndexSource(*source, type);
+}
+
+/**
+ * Set the index source for the encoder.
+ *
+ * When this source is activated, the encoder count automatically resets.
+ *
+ * @param channel A digital source to set as the encoder index
+ * @param type    The state that will cause the encoder to reset
+ */
+void Encoder::SetIndexSource(const DigitalSource& source,
+                             Encoder::IndexingType type) {
+  int32_t status = 0;
+  HAL_SetEncoderIndexSource(
+      m_encoder, source.GetPortHandleForRouting(),
+      (HAL_AnalogTriggerType)source.GetAnalogTriggerTypeForRouting(),
+      (HAL_EncoderIndexingType)type, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int Encoder::GetFPGAIndex() const {
+  int32_t status = 0;
+  int val = HAL_GetEncoderFPGAIndex(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return val;
+}
+
+void Encoder::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Speed", GetRate());
+    m_table->PutNumber("Distance", GetDistance());
+    int32_t status = 0;
+    double distancePerPulse =
+        HAL_GetEncoderDistancePerPulse(m_encoder, &status);
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+    m_table->PutNumber("Distance per Tick", distancePerPulse);
+  }
+}
+
+void Encoder::StartLiveWindowMode() {}
+
+void Encoder::StopLiveWindowMode() {}
+
+std::string Encoder::GetSmartDashboardType() const {
+  int32_t status = 0;
+  HAL_EncoderEncodingType type = HAL_GetEncoderEncodingType(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  if (type == HAL_EncoderEncodingType::HAL_Encoder_k4X)
+    return "Quadrature Encoder";
+  else
+    return "Encoder";
+}
+
+void Encoder::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> Encoder::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/GearTooth.cpp b/wpilibc/athena/src/GearTooth.cpp
new file mode 100644
index 0000000..210f12d
--- /dev/null
+++ b/wpilibc/athena/src/GearTooth.cpp
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "GearTooth.h"
+
+#include "LiveWindow/LiveWindow.h"
+
+using namespace frc;
+
+constexpr double GearTooth::kGearToothThreshold;
+
+/**
+ * Common code called by the constructors.
+ */
+void GearTooth::EnableDirectionSensing(bool directionSensitive) {
+  if (directionSensitive) {
+    SetPulseLengthMode(kGearToothThreshold);
+  }
+}
+
+/**
+ * Construct a GearTooth sensor given a channel.
+ *
+ * @param channel            The DIO channel that the sensor is connected to.
+ *                           0-9 are on-board, 10-25 are on the MXP.
+ * @param directionSensitive True to enable the pulse length decoding in
+ *                           hardware to specify count direction.
+ */
+GearTooth::GearTooth(int channel, bool directionSensitive) : Counter(channel) {
+  EnableDirectionSensing(directionSensitive);
+  LiveWindow::GetInstance()->AddSensor("GearTooth", channel, this);
+}
+
+/**
+ * Construct a GearTooth sensor given a digital input.
+ *
+ * This should be used when sharing digital inputs.
+ *
+ * @param source             A pointer to the existing DigitalSource object
+ *                           (such as a DigitalInput)
+ * @param directionSensitive True to enable the pulse length decoding in
+ *                           hardware to specify count direction.
+ */
+GearTooth::GearTooth(DigitalSource* source, bool directionSensitive)
+    : Counter(source) {
+  EnableDirectionSensing(directionSensitive);
+}
+
+/**
+ * Construct a GearTooth sensor given a digital input.
+ *
+ * This should be used when sharing digital inputs.
+ *
+ * @param source             A reference to the existing DigitalSource object
+ *                           (such as a DigitalInput)
+ * @param directionSensitive True to enable the pulse length decoding in
+ *                           hardware to specify count direction.
+ */
+GearTooth::GearTooth(std::shared_ptr<DigitalSource> source,
+                     bool directionSensitive)
+    : Counter(source) {
+  EnableDirectionSensing(directionSensitive);
+}
+
+std::string GearTooth::GetSmartDashboardType() const { return "GearTooth"; }
diff --git a/wpilibc/athena/src/GenericHID.cpp b/wpilibc/athena/src/GenericHID.cpp
new file mode 100644
index 0000000..8878276
--- /dev/null
+++ b/wpilibc/athena/src/GenericHID.cpp
@@ -0,0 +1,129 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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 "GenericHID.h"
+
+#include "DriverStation.h"
+#include "HAL/HAL.h"
+
+using namespace frc;
+
+GenericHID::GenericHID(int port) : m_ds(DriverStation::GetInstance()) {
+  m_port = port;
+}
+
+/**
+ * Get the value of the axis.
+ *
+ * @param axis The axis to read, starting at 0.
+ * @return The value of the axis.
+ */
+double GenericHID::GetRawAxis(int axis) const {
+  return m_ds.GetStickAxis(m_port, axis);
+}
+
+/**
+ * Get the button value (starting at button 1)
+ *
+ * The buttons are returned in a single 16 bit value with one bit representing
+ * the state of each button. The appropriate button is returned as a boolean
+ * value.
+ *
+ * @param button The button number to be read (starting at 1)
+ * @return The state of the button.
+ **/
+bool GenericHID::GetRawButton(int button) const {
+  return m_ds.GetStickButton(m_port, button);
+}
+
+/**
+ * Get the angle in degrees of a POV on the HID.
+ *
+ * The POV angles start at 0 in the up direction, and increase clockwise
+ * (e.g. right is 90, upper-left is 315).
+ *
+ * @param pov The index of the POV to read (starting at 0)
+ * @return the angle of the POV in degrees, or -1 if the POV is not pressed.
+ */
+int GenericHID::GetPOV(int pov) const {
+  return m_ds.GetStickPOV(GetPort(), pov);
+}
+
+/**
+ * Get the number of POVs for the HID.
+ *
+ * @return the number of POVs for the current HID
+ */
+int GenericHID::GetPOVCount() const { return m_ds.GetStickPOVCount(GetPort()); }
+
+/**
+ * Get the port number of the HID.
+ *
+ * @return The port number of the HID.
+ */
+int GenericHID::GetPort() const { return m_port; }
+
+/**
+ * Get the type of the HID.
+ *
+ * @return the type of the HID.
+ */
+GenericHID::HIDType GenericHID::GetType() const {
+  return static_cast<HIDType>(m_ds.GetJoystickType(m_port));
+}
+
+/**
+ * Get the name of the HID.
+ *
+ * @return the name of the HID.
+ */
+std::string GenericHID::GetName() const { return m_ds.GetJoystickName(m_port); }
+
+/**
+ * Set a single HID output value for the HID.
+ *
+ * @param outputNumber The index of the output to set (1-32)
+ * @param value        The value to set the output to
+ */
+
+void GenericHID::SetOutput(int outputNumber, bool value) {
+  m_outputs =
+      (m_outputs & ~(1 << (outputNumber - 1))) | (value << (outputNumber - 1));
+
+  HAL_SetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
+}
+
+/**
+ * Set all output values for the HID.
+ *
+ * @param value The 32 bit output value (1 bit for each output)
+ */
+void GenericHID::SetOutputs(int value) {
+  m_outputs = value;
+  HAL_SetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
+}
+
+/**
+ * Set the rumble output for the HID.
+ *
+ * The DS currently supports 2 rumble values, left rumble and right rumble.
+ *
+ * @param type  Which rumble value to set
+ * @param value The normalized value (0 to 1) to set the rumble to
+ */
+void GenericHID::SetRumble(RumbleType type, double value) {
+  if (value < 0)
+    value = 0;
+  else if (value > 1)
+    value = 1;
+  if (type == kLeftRumble) {
+    m_leftRumble = value * 65535;
+  } else {
+    m_rightRumble = value * 65535;
+  }
+  HAL_SetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
+}
diff --git a/wpilibc/athena/src/I2C.cpp b/wpilibc/athena/src/I2C.cpp
new file mode 100644
index 0000000..0f010f5
--- /dev/null
+++ b/wpilibc/athena/src/I2C.cpp
@@ -0,0 +1,195 @@
+/*----------------------------------------------------------------------------*/
+/* 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/I2C.h"
+#include "I2C.h"
+
+#include "HAL/HAL.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Constructor.
+ *
+ * @param port          The I2C port to which the device is connected.
+ * @param deviceAddress The address of the device on the I2C bus.
+ */
+I2C::I2C(Port port, int deviceAddress)
+    : m_port(port), m_deviceAddress(deviceAddress) {
+  int32_t status = 0;
+  HAL_InitializeI2C(m_port, &status);
+  // wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  HAL_Report(HALUsageReporting::kResourceType_I2C, deviceAddress);
+}
+
+/**
+ * Destructor.
+ */
+I2C::~I2C() { HAL_CloseI2C(m_port); }
+
+/**
+ * Generic transaction.
+ *
+ * This is a lower-level interface to the I2C hardware giving you more control
+ * over each transaction.
+ *
+ * @param dataToSend   Buffer of data to send as part of the transaction.
+ * @param sendSize     Number of bytes to send as part of the transaction.
+ * @param dataReceived Buffer to read data into.
+ * @param receiveSize  Number of bytes to read from the device.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::Transaction(uint8_t* dataToSend, int sendSize, uint8_t* dataReceived,
+                      int receiveSize) {
+  int32_t status = 0;
+  status = HAL_TransactionI2C(m_port, m_deviceAddress, dataToSend, sendSize,
+                              dataReceived, receiveSize);
+  // wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return status < receiveSize;
+}
+
+/**
+ * Attempt to address a device on the I2C bus.
+ *
+ * This allows you to figure out if there is a device on the I2C bus that
+ * responds to the address specified in the constructor.
+ *
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::AddressOnly() { return Transaction(nullptr, 0, nullptr, 0); }
+
+/**
+ * Execute a write transaction with the device.
+ *
+ * Write a single byte to a register on a device and wait until the
+ *   transaction is complete.
+ *
+ * @param registerAddress The address of the register on the device to be
+ *                        written.
+ * @param data            The byte to write to the register on the device.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::Write(int registerAddress, uint8_t data) {
+  uint8_t buffer[2];
+  buffer[0] = registerAddress;
+  buffer[1] = data;
+  int32_t status = 0;
+  status = HAL_WriteI2C(m_port, m_deviceAddress, buffer, sizeof(buffer));
+  return status < static_cast<int>(sizeof(buffer));
+}
+
+/**
+ * Execute a bulk write transaction with the device.
+ *
+ * Write multiple bytes to a device and wait until the
+ *   transaction is complete.
+ *
+ * @param data  The data to write to the register on the device.
+ * @param count The number of bytes to be written.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::WriteBulk(uint8_t* data, int count) {
+  int32_t status = 0;
+  status = HAL_WriteI2C(m_port, m_deviceAddress, data, count);
+  return status < count;
+}
+
+/**
+ * Execute a read transaction with the device.
+ *
+ * Read bytes from a device.
+ * Most I2C devices will auto-increment the register pointer internally allowing
+ * you to read consecutive registers on a device in a single transaction.
+ *
+ * @param registerAddress The register to read first in the transaction.
+ * @param count           The number of bytes to read in the transaction.
+ * @param buffer          A pointer to the array of bytes to store the data
+ *                        read from the device.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::Read(int registerAddress, int count, uint8_t* buffer) {
+  if (count < 1) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange, "count");
+    return true;
+  }
+  if (buffer == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "buffer");
+    return true;
+  }
+  return Transaction(reinterpret_cast<uint8_t*>(&registerAddress),
+                     sizeof(registerAddress), buffer, count);
+}
+
+/**
+ * Execute a read only transaction with the device.
+ *
+ * Read bytes from a device. This method does not write any data to prompt the
+ * device.
+ *
+ * @param buffer A pointer to the array of bytes to store the data read from
+ *               the device.
+ * @param count  The number of bytes to read in the transaction.
+ * @return Transfer Aborted... false for success, true for aborted.
+ */
+bool I2C::ReadOnly(int count, uint8_t* buffer) {
+  if (count < 1) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange, "count");
+    return true;
+  }
+  if (buffer == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "buffer");
+    return true;
+  }
+  int32_t status = 0;
+  status = HAL_ReadI2C(m_port, m_deviceAddress, buffer, count);
+  return status < count;
+}
+
+/**
+ * Send a broadcast write to all devices on the I2C bus.
+ *
+ * This is not currently implemented!
+ *
+ * @param registerAddress The register to write on all devices on the bus.
+ * @param data            The value to write to the devices.
+ */
+// [[gnu::warning("I2C::Broadcast() is not implemented.")]] void I2C::Broadcast(
+//     int registerAddress, uint8_t data) {}
+
+/**
+ * Verify that a device's registers contain expected values.
+ *
+ * Most devices will have a set of registers that contain a known value that
+ * can be used to identify them.  This allows an I2C device driver to easily
+ * verify that the device contains the expected value.
+ *
+ * @pre The device must support and be configured to use register
+ * auto-increment.
+ *
+ * @param registerAddress The base register to start reading from the device.
+ * @param count           The size of the field to be verified.
+ * @param expected        A buffer containing the values expected from the
+ *                        device.
+ */
+bool I2C::VerifySensor(int registerAddress, int count,
+                       const uint8_t* expected) {
+  // TODO: Make use of all 7 read bytes
+  uint8_t deviceData[4];
+  for (int i = 0, curRegisterAddress = registerAddress; i < count;
+       i += 4, curRegisterAddress += 4) {
+    int toRead = count - i < 4 ? count - i : 4;
+    // Read the chunk of data.  Return false if the sensor does not respond.
+    if (Read(curRegisterAddress, toRead, deviceData)) return false;
+
+    for (int j = 0; j < toRead; j++) {
+      if (deviceData[j] != expected[i + j]) return false;
+    }
+  }
+  return true;
+}
diff --git a/wpilibc/athena/src/Internal/HardwareHLReporting.cpp b/wpilibc/athena/src/Internal/HardwareHLReporting.cpp
new file mode 100644
index 0000000..8c66d1c
--- /dev/null
+++ b/wpilibc/athena/src/Internal/HardwareHLReporting.cpp
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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 "Internal/HardwareHLReporting.h"
+
+#include "HAL/HAL.h"
+
+using namespace frc;
+
+void HardwareHLReporting::ReportScheduler() {
+  HAL_Report(HALUsageReporting::kResourceType_Command,
+             HALUsageReporting::kCommand_Scheduler);
+}
+
+void HardwareHLReporting::ReportSmartDashboard() {
+  HAL_Report(HALUsageReporting::kResourceType_SmartDashboard, 0);
+}
diff --git a/wpilibc/athena/src/InterruptableSensorBase.cpp b/wpilibc/athena/src/InterruptableSensorBase.cpp
new file mode 100644
index 0000000..f5a006d
--- /dev/null
+++ b/wpilibc/athena/src/InterruptableSensorBase.cpp
@@ -0,0 +1,196 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "InterruptableSensorBase.h"
+
+#include "HAL/HAL.h"
+#include "Utility.h"
+#include "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));
+
+  return static_cast<WaitResult>(result);
+}
+
+/**
+ * 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/wpilibc/athena/src/IterativeRobot.cpp b/wpilibc/athena/src/IterativeRobot.cpp
new file mode 100644
index 0000000..3b4e64f
--- /dev/null
+++ b/wpilibc/athena/src/IterativeRobot.cpp
@@ -0,0 +1,263 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "IterativeRobot.h"
+
+#include "DriverStation.h"
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.h"
+#include "networktables/NetworkTable.h"
+
+using namespace frc;
+
+/**
+ * Provide an alternate "main loop" via StartCompetition().
+ *
+ * This specific StartCompetition() implements "main loop" behaviour synced with
+ * the DS packets.
+ */
+void IterativeRobot::StartCompetition() {
+  HAL_Report(HALUsageReporting::kResourceType_Framework,
+             HALUsageReporting::kFramework_Iterative);
+
+  LiveWindow* lw = LiveWindow::GetInstance();
+  // first and one-time initialization
+  NetworkTable::GetTable("LiveWindow")
+      ->GetSubTable("~STATUS~")
+      ->PutBoolean("LW Enabled", false);
+  RobotInit();
+
+  // Tell the DS that the robot is ready to be enabled
+  HAL_ObserveUserProgramStarting();
+
+  // loop forever, calling the appropriate mode-dependent function
+  lw->SetEnabled(false);
+  while (true) {
+    // wait for driver station data so the loop doesn't hog the CPU
+    m_ds.WaitForData();
+    // Call the appropriate function depending upon the current robot mode
+    if (IsDisabled()) {
+      // call DisabledInit() if we are now just entering disabled mode from
+      // either a different mode or from power-on
+      if (!m_disabledInitialized) {
+        lw->SetEnabled(false);
+        DisabledInit();
+        m_disabledInitialized = true;
+        // reset the initialization flags for the other modes
+        m_autonomousInitialized = false;
+        m_teleopInitialized = false;
+        m_testInitialized = false;
+      }
+      HAL_ObserveUserProgramDisabled();
+      DisabledPeriodic();
+    } else if (IsAutonomous()) {
+      // call AutonomousInit() if we are now just entering autonomous mode from
+      // either a different mode or from power-on
+      if (!m_autonomousInitialized) {
+        lw->SetEnabled(false);
+        AutonomousInit();
+        m_autonomousInitialized = true;
+        // reset the initialization flags for the other modes
+        m_disabledInitialized = false;
+        m_teleopInitialized = false;
+        m_testInitialized = false;
+      }
+      HAL_ObserveUserProgramAutonomous();
+      AutonomousPeriodic();
+    } else if (IsTest()) {
+      // call TestInit() if we are now just entering test mode from
+      // either a different mode or from power-on
+      if (!m_testInitialized) {
+        lw->SetEnabled(true);
+        TestInit();
+        m_testInitialized = true;
+        // reset the initialization flags for the other modes
+        m_disabledInitialized = false;
+        m_autonomousInitialized = false;
+        m_teleopInitialized = false;
+      }
+      HAL_ObserveUserProgramTest();
+      TestPeriodic();
+    } else {
+      // call TeleopInit() if we are now just entering teleop mode from
+      // either a different mode or from power-on
+      if (!m_teleopInitialized) {
+        lw->SetEnabled(false);
+        TeleopInit();
+        m_teleopInitialized = true;
+        // reset the initialization flags for the other modes
+        m_disabledInitialized = false;
+        m_autonomousInitialized = false;
+        m_testInitialized = false;
+        Scheduler::GetInstance()->SetEnabled(true);
+      }
+      HAL_ObserveUserProgramTeleop();
+      TeleopPeriodic();
+    }
+    RobotPeriodic();
+  }
+}
+
+/**
+ * Robot-wide initialization code should go here.
+ *
+ * Users should override this method for default Robot-wide initialization which
+ * will be called when the robot is first powered on. It will be called exactly
+ * one time.
+ *
+ * Warning: the Driver Station "Robot Code" light and FMS "Robot Ready"
+ * indicators will be off until RobotInit() exits. Code in RobotInit() that
+ * waits for enable will cause the robot to never indicate that the code is
+ * ready, causing the robot to be bypassed in a match.
+ */
+void IterativeRobot::RobotInit() {
+  std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
+}
+
+/**
+ * Initialization code for disabled mode should go here.
+ *
+ * Users should override this method for initialization code which will be
+ * called each time
+ * the robot enters disabled mode.
+ */
+void IterativeRobot::DisabledInit() {
+  std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
+}
+
+/**
+ * Initialization code for autonomous mode should go here.
+ *
+ * Users should override this method for initialization code which will be
+ * called each time the robot enters autonomous mode.
+ */
+void IterativeRobot::AutonomousInit() {
+  std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
+}
+
+/**
+ * Initialization code for teleop mode should go here.
+ *
+ * Users should override this method for initialization code which will be
+ * called each time the robot enters teleop mode.
+ */
+void IterativeRobot::TeleopInit() {
+  std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
+}
+
+/**
+ * Initialization code for test mode should go here.
+ *
+ * Users should override this method for initialization code which will be
+ * called each time the robot enters test mode.
+ */
+void IterativeRobot::TestInit() {
+  std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
+}
+
+/**
+ * Periodic code for all modes should go here.
+ *
+ * This function is called each time a new packet is received from the driver
+ * station.
+ *
+ * Packets are received approximately every 20ms. Fixed loop timing is not
+ * guaranteed due to network timing variability and the function may not be
+ * called at all if the Driver Station is disconnected. For most use cases the
+ * variable timing will not be an issue. If your code does require guaranteed
+ * fixed periodic timing, consider using Notifier or PIDController instead.
+ */
+void IterativeRobot::RobotPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
+    firstRun = false;
+  }
+}
+
+/**
+ * Periodic code for disabled mode should go here.
+ *
+ * Users should override this method for code which will be called each time a
+ * new packet is received from the driver station and the robot is in disabled
+ * mode.
+ *
+ * Packets are received approximately every 20ms. Fixed loop timing is not
+ * guaranteed due to network timing variability and the function may not be
+ * called at all if the Driver Station is disconnected. For most use cases the
+ * variable timing will not be an issue. If your code does require guaranteed
+ * fixed periodic timing, consider using Notifier or PIDController instead.
+ */
+void IterativeRobot::DisabledPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
+    firstRun = false;
+  }
+}
+
+/**
+ * Periodic code for autonomous mode should go here.
+ *
+ * Users should override this method for code which will be called each time a
+ * new packet is received from the driver station and the robot is in autonomous
+ * mode.
+ *
+ * Packets are received approximately every 20ms. Fixed loop timing is not
+ * guaranteed due to network timing variability and the function may not be
+ * called at all if the Driver Station is disconnected. For most use cases the
+ * variable timing will not be an issue. If your code does require guaranteed
+ * fixed periodic timing, consider using Notifier or PIDController instead.
+ */
+void IterativeRobot::AutonomousPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
+    firstRun = false;
+  }
+}
+
+/**
+ * Periodic code for teleop mode should go here.
+ *
+ * Users should override this method for code which will be called each time a
+ * new packet is received from the driver station and the robot is in teleop
+ * mode.
+ *
+ * Packets are received approximately every 20ms. Fixed loop timing is not
+ * guaranteed due to network timing variability and the function may not be
+ * called at all if the Driver Station is disconnected. For most use cases the
+ * variable timing will not be an issue. If your code does require guaranteed
+ * fixed periodic timing, consider using Notifier or PIDController instead.
+ */
+void IterativeRobot::TeleopPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
+    firstRun = false;
+  }
+}
+
+/**
+ * Periodic code for test mode should go here.
+ *
+ * Users should override this method for code which will be called each time a
+ * new packet is received from the driver station and the robot is in test mode.
+ *
+ * Packets are received approximately every 20ms. Fixed loop timing is not
+ * guaranteed due to network timing variability and the function may not be
+ * called at all if the Driver Station is disconnected. For most use cases the
+ * variable timing will not be an issue. If your code does require guaranteed
+ * fixed periodic timing, consider using Notifier or PIDController instead.
+ */
+void IterativeRobot::TestPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
+    firstRun = false;
+  }
+}
diff --git a/wpilibc/athena/src/Jaguar.cpp b/wpilibc/athena/src/Jaguar.cpp
new file mode 100644
index 0000000..1d6cce8
--- /dev/null
+++ b/wpilibc/athena/src/Jaguar.cpp
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Jaguar.h"
+
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.h"
+
+using namespace frc;
+
+/**
+ * Constructor for a Jaguar connected via PWM.
+ *
+ * @param channel The PWM channel that the Jaguar is attached to. 0-9 are
+ *                on-board, 10-19 are on the MXP port
+ */
+Jaguar::Jaguar(int channel) : PWMSpeedController(channel) {
+  /**
+   * Input profile defined by Luminary Micro.
+   *
+   * Full reverse ranges from 0.671325ms to 0.6972211ms
+   * Proportional reverse ranges from 0.6972211ms to 1.4482078ms
+   * Neutral ranges from 1.4482078ms to 1.5517922ms
+   * Proportional forward ranges from 1.5517922ms to 2.3027789ms
+   * Full forward ranges from 2.3027789ms to 2.328675ms
+   */
+  SetBounds(2.31, 1.55, 1.507, 1.454, .697);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_Jaguar, GetChannel());
+  LiveWindow::GetInstance()->AddActuator("Jaguar", GetChannel(), this);
+}
diff --git a/wpilibc/athena/src/Joystick.cpp b/wpilibc/athena/src/Joystick.cpp
new file mode 100644
index 0000000..809950b
--- /dev/null
+++ b/wpilibc/athena/src/Joystick.cpp
@@ -0,0 +1,281 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Joystick.h"
+
+#include <cmath>
+
+#include "DriverStation.h"
+#include "HAL/HAL.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+const int Joystick::kDefaultXAxis;
+const int Joystick::kDefaultYAxis;
+const int Joystick::kDefaultZAxis;
+const int Joystick::kDefaultTwistAxis;
+const int Joystick::kDefaultThrottleAxis;
+const int Joystick::kDefaultTriggerButton;
+const int Joystick::kDefaultTopButton;
+static Joystick* joysticks[DriverStation::kJoystickPorts];
+static bool joySticksInitialized = false;
+
+/**
+ * Construct an instance of a joystick.
+ *
+ * The joystick index is the USB port on the Driver Station.
+ *
+ * @param port The port on the Driver Station that the joystick is plugged into
+ *             (0-5).
+ */
+Joystick::Joystick(int port) : Joystick(port, kNumAxisTypes, kNumButtonTypes) {
+  m_axes[kXAxis] = kDefaultXAxis;
+  m_axes[kYAxis] = kDefaultYAxis;
+  m_axes[kZAxis] = kDefaultZAxis;
+  m_axes[kTwistAxis] = kDefaultTwistAxis;
+  m_axes[kThrottleAxis] = kDefaultThrottleAxis;
+
+  m_buttons[kTriggerButton] = kDefaultTriggerButton;
+  m_buttons[kTopButton] = kDefaultTopButton;
+
+  HAL_Report(HALUsageReporting::kResourceType_Joystick, port);
+}
+
+/**
+ * Version of the constructor to be called by sub-classes.
+ *
+ * This constructor allows the subclass to configure the number of constants
+ * for axes and buttons.
+ *
+ * @param port           The port on the Driver Station that the joystick is
+ *                       plugged into.
+ * @param numAxisTypes   The number of axis types in the enum.
+ * @param numButtonTypes The number of button types in the enum.
+ */
+Joystick::Joystick(int port, int numAxisTypes, int numButtonTypes)
+    : JoystickBase(port),
+      m_ds(DriverStation::GetInstance()),
+      m_axes(numAxisTypes),
+      m_buttons(numButtonTypes) {
+  if (!joySticksInitialized) {
+    for (auto& joystick : joysticks) joystick = nullptr;
+    joySticksInitialized = true;
+  }
+  if (GetPort() >= DriverStation::kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+  } else {
+    joysticks[GetPort()] = this;
+  }
+}
+
+Joystick* Joystick::GetStickForPort(int port) {
+  Joystick* stick = joysticks[port];
+  if (stick == nullptr) {
+    stick = new Joystick(port);
+    joysticks[port] = stick;
+  }
+  return stick;
+}
+
+/**
+ * Get the X value of the joystick.
+ *
+ * This depends on the mapping of the joystick connected to the current port.
+ *
+ * @param hand This parameter is ignored for the Joystick class and is only
+ *             here to complete the GenericHID interface.
+ */
+double Joystick::GetX(JoystickHand hand) const {
+  return GetRawAxis(m_axes[kXAxis]);
+}
+
+/**
+ * Get the Y value of the joystick.
+ *
+ * This depends on the mapping of the joystick connected to the current port.
+ *
+ * @param hand This parameter is ignored for the Joystick class and is only
+ *             here to complete the GenericHID interface.
+ */
+double Joystick::GetY(JoystickHand hand) const {
+  return GetRawAxis(m_axes[kYAxis]);
+}
+
+/**
+ * Get the Z value of the current joystick.
+ *
+ * This depends on the mapping of the joystick connected to the current port.
+ */
+double Joystick::GetZ(JoystickHand hand) const {
+  return GetRawAxis(m_axes[kZAxis]);
+}
+
+/**
+ * Get the twist value of the current joystick.
+ *
+ * This depends on the mapping of the joystick connected to the current port.
+ */
+double Joystick::GetTwist() const { return GetRawAxis(m_axes[kTwistAxis]); }
+
+/**
+ * Get the throttle value of the current joystick.
+ *
+ * This depends on the mapping of the joystick connected to the current port.
+ */
+double Joystick::GetThrottle() const {
+  return GetRawAxis(m_axes[kThrottleAxis]);
+}
+
+/**
+ * For the current joystick, return the axis determined by the argument.
+ *
+ * This is for cases where the joystick axis is returned programatically,
+ * otherwise one of the previous functions would be preferable (for example
+ * GetX()).
+ *
+ * @param axis The axis to read.
+ * @return The value of the axis.
+ */
+double Joystick::GetAxis(AxisType axis) const {
+  switch (axis) {
+    case kXAxis:
+      return this->GetX();
+    case kYAxis:
+      return this->GetY();
+    case kZAxis:
+      return this->GetZ();
+    case kTwistAxis:
+      return this->GetTwist();
+    case kThrottleAxis:
+      return this->GetThrottle();
+    default:
+      wpi_setWPIError(BadJoystickAxis);
+      return 0.0;
+  }
+}
+
+/**
+ * Read the state of the trigger on the joystick.
+ *
+ * Look up which button has been assigned to the trigger and read its state.
+ *
+ * @param hand This parameter is ignored for the Joystick class and is only
+ *             here to complete the GenericHID interface.
+ * @return The state of the trigger.
+ */
+bool Joystick::GetTrigger(JoystickHand hand) const {
+  return GetRawButton(m_buttons[kTriggerButton]);
+}
+
+/**
+ * Read the state of the top button on the joystick.
+ *
+ * Look up which button has been assigned to the top and read its state.
+ *
+ * @param hand This parameter is ignored for the Joystick class and is only
+ *             here to complete the GenericHID interface.
+ * @return The state of the top button.
+ */
+bool Joystick::GetTop(JoystickHand hand) const {
+  return GetRawButton(m_buttons[kTopButton]);
+}
+
+/**
+ * Get buttons based on an enumerated type.
+ *
+ * The button type will be looked up in the list of buttons and then read.
+ *
+ * @param button The type of button to read.
+ * @return The state of the button.
+ */
+bool Joystick::GetButton(ButtonType button) const {
+  switch (button) {
+    case kTriggerButton:
+      return GetTrigger();
+    case kTopButton:
+      return GetTop();
+    default:
+      return false;
+  }
+}
+
+/**
+ * Get the number of axis for a joystick
+ *
+ * @return the number of axis for the current joystick
+ */
+int Joystick::GetAxisCount() const { return m_ds.GetStickAxisCount(GetPort()); }
+
+/**
+ * Get the axis type of a joystick axis.
+ *
+ * @return the axis type of a joystick axis.
+ */
+int Joystick::GetAxisType(int axis) const {
+  return m_ds.GetJoystickAxisType(GetPort(), axis);
+}
+
+/**
+ * Get the number of buttons for a joystick.
+ *
+ * @return the number of buttons on the current joystick
+ */
+int Joystick::GetButtonCount() const {
+  return m_ds.GetStickButtonCount(GetPort());
+}
+
+/**
+ * Get the channel currently associated with the specified axis.
+ *
+ * @param axis The axis to look up the channel for.
+ * @return The channel fr the axis.
+ */
+int Joystick::GetAxisChannel(AxisType axis) const { return m_axes[axis]; }
+
+/**
+ * Set the channel associated with a specified axis.
+ *
+ * @param axis    The axis to set the channel for.
+ * @param channel The channel to set the axis to.
+ */
+void Joystick::SetAxisChannel(AxisType axis, int channel) {
+  m_axes[axis] = channel;
+}
+
+/**
+ * Get the magnitude of the direction vector formed by the joystick's
+ * current position relative to its origin.
+ *
+ * @return The magnitude of the direction vector
+ */
+double Joystick::GetMagnitude() const {
+  return std::sqrt(std::pow(GetX(), 2) + std::pow(GetY(), 2));
+}
+
+/**
+ * Get the direction of the vector formed by the joystick and its origin
+ * in radians.
+ *
+ * @return The direction of the vector in radians
+ */
+double Joystick::GetDirectionRadians() const {
+  return std::atan2(GetX(), -GetY());
+}
+
+/**
+ * Get the direction of the vector formed by the joystick and its origin
+ * in degrees.
+ *
+ * uses std::acos(-1) to represent Pi due to absence of readily accessible Pi
+ * constant in C++
+ *
+ * @return The direction of the vector in degrees
+ */
+double Joystick::GetDirectionDegrees() const {
+  return (180 / std::acos(-1)) * GetDirectionRadians();
+}
diff --git a/wpilibc/athena/src/MotorSafetyHelper.cpp b/wpilibc/athena/src/MotorSafetyHelper.cpp
new file mode 100644
index 0000000..9f1ee89
--- /dev/null
+++ b/wpilibc/athena/src/MotorSafetyHelper.cpp
@@ -0,0 +1,136 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "MotorSafetyHelper.h"
+
+#include <sstream>
+
+#include "DriverStation.h"
+#include "MotorSafety.h"
+#include "Timer.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+std::set<MotorSafetyHelper*> MotorSafetyHelper::m_helperList;
+priority_recursive_mutex MotorSafetyHelper::m_listMutex;
+
+/**
+ * The constructor for a MotorSafetyHelper object.
+ *
+ * The helper object is constructed for every object that wants to implement the
+ * Motor Safety protocol. The helper object has the code to actually do the
+ * timing and call the motors Stop() method when the timeout expires. The motor
+ * object is expected to call the Feed() method whenever the motors value is
+ * updated.
+ *
+ * @param safeObject a pointer to the motor object implementing MotorSafety.
+ *                   This is used to call the Stop() method on the motor.
+ */
+MotorSafetyHelper::MotorSafetyHelper(MotorSafety* safeObject)
+    : m_safeObject(safeObject) {
+  m_enabled = false;
+  m_expiration = DEFAULT_SAFETY_EXPIRATION;
+  m_stopTime = Timer::GetFPGATimestamp();
+
+  std::lock_guard<priority_recursive_mutex> sync(m_listMutex);
+  m_helperList.insert(this);
+}
+
+MotorSafetyHelper::~MotorSafetyHelper() {
+  std::lock_guard<priority_recursive_mutex> sync(m_listMutex);
+  m_helperList.erase(this);
+}
+
+/**
+ * Feed the motor safety object.
+ * Resets the timer on this object that is used to do the timeouts.
+ */
+void MotorSafetyHelper::Feed() {
+  std::lock_guard<priority_recursive_mutex> sync(m_syncMutex);
+  m_stopTime = Timer::GetFPGATimestamp() + m_expiration;
+}
+
+/**
+ * Set the expiration time for the corresponding motor safety object.
+ * @param expirationTime The timeout value in seconds.
+ */
+void MotorSafetyHelper::SetExpiration(double expirationTime) {
+  std::lock_guard<priority_recursive_mutex> sync(m_syncMutex);
+  m_expiration = expirationTime;
+}
+
+/**
+ * Retrieve the timeout value for the corresponding motor safety object.
+ * @return the timeout value in seconds.
+ */
+double MotorSafetyHelper::GetExpiration() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_syncMutex);
+  return m_expiration;
+}
+
+/**
+ * Determine if the motor is still operating or has timed out.
+ * @return a true value if the motor is still operating normally and hasn't
+ * timed out.
+ */
+bool MotorSafetyHelper::IsAlive() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_syncMutex);
+  return !m_enabled || m_stopTime > Timer::GetFPGATimestamp();
+}
+
+/**
+ * Check if this motor has exceeded its timeout.
+ * This method is called periodically to determine if this motor has exceeded
+ * its timeout value. If it has, the stop method is called, and the motor is
+ * shut down until its value is updated again.
+ */
+void MotorSafetyHelper::Check() {
+  DriverStation& ds = DriverStation::GetInstance();
+  if (!m_enabled || ds.IsDisabled() || ds.IsTest()) return;
+
+  std::lock_guard<priority_recursive_mutex> sync(m_syncMutex);
+  if (m_stopTime < Timer::GetFPGATimestamp()) {
+    std::ostringstream desc;
+    m_safeObject->GetDescription(desc);
+    desc << "... Output not updated often enough.";
+    wpi_setWPIErrorWithContext(Timeout, desc.str().c_str());
+    m_safeObject->StopMotor();
+  }
+}
+
+/**
+ * Enable/disable motor safety for this device
+ * Turn on and off the motor safety option for this PWM object.
+ * @param enabled True if motor safety is enforced for this object
+ */
+void MotorSafetyHelper::SetSafetyEnabled(bool enabled) {
+  std::lock_guard<priority_recursive_mutex> sync(m_syncMutex);
+  m_enabled = enabled;
+}
+
+/**
+ * Return the state of the motor safety enabled flag
+ * Return if the motor safety is currently enabled for this devicce.
+ * @return True if motor safety is enforced for this device
+ */
+bool MotorSafetyHelper::IsSafetyEnabled() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_syncMutex);
+  return m_enabled;
+}
+
+/**
+ * Check the motors to see if any have timed out.
+ * This static  method is called periodically to poll all the motors and stop
+ * any that have timed out.
+ */
+void MotorSafetyHelper::CheckMotors() {
+  std::lock_guard<priority_recursive_mutex> sync(m_listMutex);
+  for (auto elem : m_helperList) {
+    elem->Check();
+  }
+}
diff --git a/wpilibc/athena/src/Notifier.cpp b/wpilibc/athena/src/Notifier.cpp
new file mode 100644
index 0000000..67abe37
--- /dev/null
+++ b/wpilibc/athena/src/Notifier.cpp
@@ -0,0 +1,141 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Notifier.h"
+
+#include "HAL/HAL.h"
+#include "Timer.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+priority_mutex Notifier::m_destructorMutex;
+
+/**
+ * Create a Notifier for timer event notification.
+ *
+ * @param handler The handler is called at the notification time which is set
+ *                using StartSingle or StartPeriodic.
+ */
+Notifier::Notifier(TimerEventHandler handler) {
+  if (handler == nullptr)
+    wpi_setWPIErrorWithContext(NullParameter, "handler must not be nullptr");
+  m_handler = handler;
+  int32_t status = 0;
+  m_notifier = HAL_InitializeNotifier(&Notifier::Notify, this, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Free the resources for a timer event.
+ */
+Notifier::~Notifier() {
+  int32_t status = 0;
+  // atomically set handle to 0, then clean
+  HAL_NotifierHandle handle = m_notifier.exchange(0);
+  HAL_CleanNotifier(handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  /* Acquire the mutex; this makes certain that the handler is not being
+   * executed by the interrupt manager.
+   */
+  std::lock_guard<priority_mutex> lockStatic(Notifier::m_destructorMutex);
+  std::lock_guard<priority_mutex> lock(m_processMutex);
+}
+
+/**
+ * Update the HAL alarm time.
+ */
+void Notifier::UpdateAlarm() {
+  int32_t status = 0;
+  // Return if we are being destructed, or were not created successfully
+  if (m_notifier == 0) return;
+  HAL_UpdateNotifierAlarm(
+      m_notifier, static_cast<uint64_t>(m_expirationTime * 1e6), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Notify is called by the HAL layer.  We simply need to pass it through to
+ * the user handler.
+ */
+void Notifier::Notify(uint64_t currentTimeInt, HAL_NotifierHandle handle) {
+  Notifier* notifier;
+  {
+    // Lock static mutex to grab the notifier param
+    std::lock_guard<priority_mutex> lock(Notifier::m_destructorMutex);
+    int32_t status = 0;
+    auto notifierPointer = HAL_GetNotifierParam(handle, &status);
+    if (notifierPointer == nullptr) return;
+    notifier = static_cast<Notifier*>(notifierPointer);
+    notifier->m_processMutex.lock();
+  }
+
+  if (notifier->m_periodic) {
+    notifier->m_expirationTime += notifier->m_period;
+    notifier->UpdateAlarm();
+  }
+
+  auto handler = notifier->m_handler;
+
+  if (handler) handler();
+  notifier->m_processMutex.unlock();
+}
+
+/**
+ * Register for single event notification.
+ *
+ * A timer event is queued for a single event after the specified delay.
+ *
+ * @param delay Seconds to wait before the handler is called.
+ */
+void Notifier::StartSingle(double delay) {
+  std::lock_guard<priority_mutex> sync(m_processMutex);
+  m_periodic = false;
+  m_period = delay;
+  m_expirationTime = GetClock() + m_period;
+  UpdateAlarm();
+}
+
+/**
+ * Register for periodic event notification.
+ *
+ * A timer event is queued for periodic event notification. Each time the
+ * interrupt occurs, the event will be immediately requeued for the same time
+ * interval.
+ *
+ * @param period Period in seconds to call the handler starting one period
+ *               after the call to this method.
+ */
+void Notifier::StartPeriodic(double period) {
+  std::lock_guard<priority_mutex> sync(m_processMutex);
+  m_periodic = true;
+  m_period = period;
+  m_expirationTime = GetClock() + m_period;
+  UpdateAlarm();
+}
+
+/**
+ * Stop timer events from occuring.
+ *
+ * Stop any repeating timer events from occuring. This will also remove any
+ * single notification events from the queue.
+ *
+ * If a timer-based call to the registered handler is in progress, this function
+ * will block until the handler call is complete.
+ */
+void Notifier::Stop() {
+  int32_t status = 0;
+  HAL_StopNotifierAlarm(m_notifier, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  // Wait for a currently executing handler to complete before returning from
+  // Stop()
+  std::lock_guard<priority_mutex> lockStatic(Notifier::m_destructorMutex);
+  std::lock_guard<priority_mutex> lock(m_processMutex);
+}
diff --git a/wpilibc/athena/src/PIDController.cpp b/wpilibc/athena/src/PIDController.cpp
new file mode 100644
index 0000000..d81d681
--- /dev/null
+++ b/wpilibc/athena/src/PIDController.cpp
@@ -0,0 +1,636 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "PIDController.h"
+
+#include <cmath>
+#include <vector>
+
+#include "HAL/HAL.h"
+#include "Notifier.h"
+#include "PIDOutput.h"
+#include "PIDSource.h"
+
+using namespace frc;
+
+static const std::string kP = "p";
+static const std::string kI = "i";
+static const std::string kD = "d";
+static const std::string kF = "f";
+static const std::string kSetpoint = "setpoint";
+static const std::string kEnabled = "enabled";
+
+/**
+ * Allocate a PID object with the given constants for P, I, D.
+ *
+ * @param Kp     the proportional coefficient
+ * @param Ki     the integral coefficient
+ * @param Kd     the derivative coefficient
+ * @param source The PIDSource object that is used to get values
+ * @param output The PIDOutput object that is set to the output value
+ * @param period the loop time for doing calculations. This particularly
+ *               effects calculations of the integral and differental terms.
+ *               The default is 50ms.
+ */
+PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource* source,
+                             PIDOutput* output, double period)
+    : PIDController(Kp, Ki, Kd, 0.0, source, output, period) {}
+
+/**
+ * Allocate a PID object with the given constants for P, I, D.
+ *
+ * @param Kp     the proportional coefficient
+ * @param Ki     the integral coefficient
+ * @param Kd     the derivative coefficient
+ * @param source The PIDSource object that is used to get values
+ * @param output The PIDOutput object that is set to the output value
+ * @param period the loop time for doing calculations. This particularly
+ *               effects calculations of the integral and differental terms.
+ *               The default is 50ms.
+ */
+PIDController::PIDController(double Kp, double Ki, double Kd, double Kf,
+                             PIDSource* source, PIDOutput* output,
+                             double period) {
+  m_controlLoop = std::make_unique<Notifier>(&PIDController::Calculate, this);
+
+  m_P = Kp;
+  m_I = Ki;
+  m_D = Kd;
+  m_F = Kf;
+
+  m_pidInput = source;
+  m_pidOutput = output;
+  m_period = period;
+
+  m_controlLoop->StartPeriodic(m_period);
+  m_setpointTimer.Start();
+
+  static int instances = 0;
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_PIDController, instances);
+}
+
+PIDController::~PIDController() {
+  // forcefully stopping the notifier so the callback can successfully run.
+  m_controlLoop->Stop();
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+}
+
+/**
+ * Read the input, calculate the output accordingly, and write to the output.
+ * This should only be called by the Notifier.
+ */
+void PIDController::Calculate() {
+  bool enabled;
+  PIDSource* pidInput;
+  PIDOutput* pidOutput;
+
+  {
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+    pidInput = m_pidInput;
+    pidOutput = m_pidOutput;
+    enabled = m_enabled;
+  }
+
+  if (pidInput == nullptr) return;
+  if (pidOutput == nullptr) return;
+
+  if (enabled) {
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+    double input = pidInput->PIDGet();
+    double result;
+    PIDOutput* pidOutput;
+
+    m_error = GetContinuousError(m_setpoint - input);
+
+    if (m_pidInput->GetPIDSourceType() == PIDSourceType::kRate) {
+      if (m_P != 0) {
+        double potentialPGain = (m_totalError + m_error) * m_P;
+        if (potentialPGain < m_maximumOutput) {
+          if (potentialPGain > m_minimumOutput)
+            m_totalError += m_error;
+          else
+            m_totalError = m_minimumOutput / m_P;
+        } else {
+          m_totalError = m_maximumOutput / m_P;
+        }
+      }
+
+      m_result = m_D * m_error + m_P * m_totalError + CalculateFeedForward();
+    } else {
+      if (m_I != 0) {
+        double potentialIGain = (m_totalError + m_error) * m_I;
+        if (potentialIGain < m_maximumOutput) {
+          if (potentialIGain > m_minimumOutput)
+            m_totalError += m_error;
+          else
+            m_totalError = m_minimumOutput / m_I;
+        } else {
+          m_totalError = m_maximumOutput / m_I;
+        }
+      }
+
+      m_result = m_P * m_error + m_I * m_totalError +
+                 m_D * (m_error - m_prevError) + CalculateFeedForward();
+    }
+    m_prevError = m_error;
+
+    if (m_result > m_maximumOutput)
+      m_result = m_maximumOutput;
+    else if (m_result < m_minimumOutput)
+      m_result = m_minimumOutput;
+
+    pidOutput = m_pidOutput;
+    result = m_result;
+
+    pidOutput->PIDWrite(result);
+
+    // Update the buffer.
+    m_buf.push(m_error);
+    m_bufTotal += m_error;
+    // Remove old elements when buffer is full.
+    if (m_buf.size() > m_bufLength) {
+      m_bufTotal -= m_buf.front();
+      m_buf.pop();
+    }
+  }
+}
+
+/**
+ * Calculate the feed forward term.
+ *
+ * Both of the provided feed forward calculations are velocity feed forwards.
+ * If a different feed forward calculation is desired, the user can override
+ * this function and provide his or her own. This function does no
+ * synchronization because the PIDController class only calls it in synchronized
+ * code, so be careful if calling it oneself.
+ *
+ * If a velocity PID controller is being used, the F term should be set to 1
+ * over the maximum setpoint for the output. If a position PID controller is
+ * being used, the F term should be set to 1 over the maximum speed for the
+ * output measured in setpoint units per this controller's update period (see
+ * the default period in this class's constructor).
+ */
+double PIDController::CalculateFeedForward() {
+  if (m_pidInput->GetPIDSourceType() == PIDSourceType::kRate) {
+    return m_F * GetSetpoint();
+  } else {
+    double temp = m_F * GetDeltaSetpoint();
+    m_prevSetpoint = m_setpoint;
+    m_setpointTimer.Reset();
+    return temp;
+  }
+}
+
+/**
+ * Set the PID Controller gain parameters.
+ *
+ * Set the proportional, integral, and differential coefficients.
+ *
+ * @param p Proportional coefficient
+ * @param i Integral coefficient
+ * @param d Differential coefficient
+ */
+void PIDController::SetPID(double p, double i, double d) {
+  {
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+    m_P = p;
+    m_I = i;
+    m_D = d;
+  }
+
+  if (m_table != nullptr) {
+    m_table->PutNumber("p", m_P);
+    m_table->PutNumber("i", m_I);
+    m_table->PutNumber("d", m_D);
+  }
+}
+
+/**
+ * Set the PID Controller gain parameters.
+ *
+ * Set the proportional, integral, and differential coefficients.
+ *
+ * @param p Proportional coefficient
+ * @param i Integral coefficient
+ * @param d Differential coefficient
+ * @param f Feed forward coefficient
+ */
+void PIDController::SetPID(double p, double i, double d, double f) {
+  {
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+    m_P = p;
+    m_I = i;
+    m_D = d;
+    m_F = f;
+  }
+
+  if (m_table != nullptr) {
+    m_table->PutNumber("p", m_P);
+    m_table->PutNumber("i", m_I);
+    m_table->PutNumber("d", m_D);
+    m_table->PutNumber("f", m_F);
+  }
+}
+
+/**
+ * Get the Proportional coefficient.
+ *
+ * @return proportional coefficient
+ */
+double PIDController::GetP() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  return m_P;
+}
+
+/**
+ * Get the Integral coefficient.
+ *
+ * @return integral coefficient
+ */
+double PIDController::GetI() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  return m_I;
+}
+
+/**
+ * Get the Differential coefficient.
+ *
+ * @return differential coefficient
+ */
+double PIDController::GetD() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  return m_D;
+}
+
+/**
+ * Get the Feed forward coefficient.
+ *
+ * @return Feed forward coefficient
+ */
+double PIDController::GetF() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  return m_F;
+}
+
+/**
+ * Return the current PID result.
+ *
+ * This is always centered on zero and constrained the the max and min outs.
+ *
+ * @return the latest calculated output
+ */
+double PIDController::Get() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  return m_result;
+}
+
+/**
+ * Set the PID controller to consider the input to be continuous,
+ *
+ * Rather then using the max and min in as constraints, it considers them to
+ * be the same point and automatically calculates the shortest route to
+ * the setpoint.
+ *
+ * @param continuous true turns on continuous, false turns off continuous
+ */
+void PIDController::SetContinuous(bool continuous) {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  m_continuous = continuous;
+}
+
+/**
+ * Sets the maximum and minimum values expected from the input.
+ *
+ * @param minimumInput the minimum value expected from the input
+ * @param maximumInput the maximum value expected from the output
+ */
+void PIDController::SetInputRange(double minimumInput, double maximumInput) {
+  {
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+    m_minimumInput = minimumInput;
+    m_maximumInput = maximumInput;
+  }
+
+  SetSetpoint(m_setpoint);
+}
+
+/**
+ * Sets the minimum and maximum values to write.
+ *
+ * @param minimumOutput the minimum value to write to the output
+ * @param maximumOutput the maximum value to write to the output
+ */
+void PIDController::SetOutputRange(double minimumOutput, double maximumOutput) {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  m_minimumOutput = minimumOutput;
+  m_maximumOutput = maximumOutput;
+}
+
+/**
+ * Set the setpoint for the PIDController.
+ *
+ * Clears the queue for GetAvgError().
+ *
+ * @param setpoint the desired setpoint
+ */
+void PIDController::SetSetpoint(double setpoint) {
+  {
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+
+    if (m_maximumInput > m_minimumInput) {
+      if (setpoint > m_maximumInput)
+        m_setpoint = m_maximumInput;
+      else if (setpoint < m_minimumInput)
+        m_setpoint = m_minimumInput;
+      else
+        m_setpoint = setpoint;
+    } else {
+      m_setpoint = setpoint;
+    }
+
+    // Clear m_buf.
+    m_buf = std::queue<double>();
+    m_bufTotal = 0;
+  }
+
+  if (m_table != nullptr) {
+    m_table->PutNumber("setpoint", m_setpoint);
+  }
+}
+
+/**
+ * Returns the current setpoint of the PIDController.
+ *
+ * @return the current setpoint
+ */
+double PIDController::GetSetpoint() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  return m_setpoint;
+}
+
+/**
+ * Returns the change in setpoint over time of the PIDController.
+ *
+ * @return the change in setpoint over time
+ */
+double PIDController::GetDeltaSetpoint() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  return (m_setpoint - m_prevSetpoint) / m_setpointTimer.Get();
+}
+
+/**
+ * Returns the current difference of the input from the setpoint.
+ *
+ * @return the current error
+ */
+double PIDController::GetError() const {
+  double setpoint = GetSetpoint();
+  {
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+    return GetContinuousError(setpoint - m_pidInput->PIDGet());
+  }
+}
+
+/**
+ * Sets what type of input the PID controller will use.
+ */
+void PIDController::SetPIDSourceType(PIDSourceType pidSource) {
+  m_pidInput->SetPIDSourceType(pidSource);
+}
+/**
+ * Returns the type of input the PID controller is using.
+ *
+ * @return the PID controller input type
+ */
+PIDSourceType PIDController::GetPIDSourceType() const {
+  return m_pidInput->GetPIDSourceType();
+}
+
+/**
+ * Returns the current average of the error over the past few iterations.
+ *
+ * You can specify the number of iterations to average with SetToleranceBuffer()
+ * (defaults to 1). This is the same value that is used for OnTarget().
+ *
+ * @return the average error
+ */
+double PIDController::GetAvgError() const {
+  double avgError = 0;
+  {
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+    // Don't divide by zero.
+    if (m_buf.size()) avgError = m_bufTotal / m_buf.size();
+  }
+  return avgError;
+}
+
+/*
+ * Set the percentage error which is considered tolerable for use with
+ * OnTarget.
+ *
+ * @param percentage error which is tolerable
+ */
+void PIDController::SetTolerance(double percent) {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  m_toleranceType = kPercentTolerance;
+  m_tolerance = percent;
+}
+
+/*
+ * Set the absolute error which is considered tolerable for use with
+ * OnTarget.
+ *
+ * @param percentage error which is tolerable
+ */
+void PIDController::SetAbsoluteTolerance(double absTolerance) {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  m_toleranceType = kAbsoluteTolerance;
+  m_tolerance = absTolerance;
+}
+
+/*
+ * Set the percentage error which is considered tolerable for use with
+ * OnTarget.
+ *
+ * @param percentage error which is tolerable
+ */
+void PIDController::SetPercentTolerance(double percent) {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  m_toleranceType = kPercentTolerance;
+  m_tolerance = percent;
+}
+
+/*
+ * Set the number of previous error samples to average for tolerancing. When
+ * determining whether a mechanism is on target, the user may want to use a
+ * rolling average of previous measurements instead of a precise position or
+ * velocity. This is useful for noisy sensors which return a few erroneous
+ * measurements when the mechanism is on target. However, the mechanism will
+ * not register as on target for at least the specified bufLength cycles.
+ *
+ * @param bufLength Number of previous cycles to average. Defaults to 1.
+ */
+void PIDController::SetToleranceBuffer(int bufLength) {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  m_bufLength = bufLength;
+
+  // Cut the buffer down to size if needed.
+  while (m_buf.size() > static_cast<uint32_t>(bufLength)) {
+    m_bufTotal -= m_buf.front();
+    m_buf.pop();
+  }
+}
+
+/*
+ * Return true if the error is within the percentage of the total input range,
+ * determined by SetTolerance. This asssumes that the maximum and minimum input
+ * were set using SetInput.
+ *
+ * Currently this just reports on target as the actual value passes through the
+ * setpoint. Ideally it should be based on being within the tolerance for some
+ * period of time.
+ *
+ * This will return false until at least one input value has been computed.
+ */
+bool PIDController::OnTarget() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  if (m_buf.size() == 0) return false;
+  double error = GetAvgError();
+  switch (m_toleranceType) {
+    case kPercentTolerance:
+      return std::fabs(error) <
+             m_tolerance / 100 * (m_maximumInput - m_minimumInput);
+      break;
+    case kAbsoluteTolerance:
+      return std::fabs(error) < m_tolerance;
+      break;
+    case kNoTolerance:
+      // TODO: this case needs an error
+      return false;
+  }
+  return false;
+}
+
+/**
+ * Begin running the PIDController.
+ */
+void PIDController::Enable() {
+  {
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+    m_enabled = true;
+  }
+
+  if (m_table != nullptr) {
+    m_table->PutBoolean("enabled", true);
+  }
+}
+
+/**
+ * Stop running the PIDController, this sets the output to zero before stopping.
+ */
+void PIDController::Disable() {
+  {
+    std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+    m_pidOutput->PIDWrite(0);
+    m_enabled = false;
+  }
+
+  if (m_table != nullptr) {
+    m_table->PutBoolean("enabled", false);
+  }
+}
+
+/**
+ * Return true if PIDController is enabled.
+ */
+bool PIDController::IsEnabled() const {
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  return m_enabled;
+}
+
+/**
+ * Reset the previous error, the integral term, and disable the controller.
+ */
+void PIDController::Reset() {
+  Disable();
+
+  std::lock_guard<priority_recursive_mutex> sync(m_mutex);
+  m_prevError = 0;
+  m_totalError = 0;
+  m_result = 0;
+}
+
+std::string PIDController::GetSmartDashboardType() const {
+  return "PIDController";
+}
+
+void PIDController::InitTable(std::shared_ptr<ITable> subtable) {
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+  m_table = subtable;
+  if (m_table != nullptr) {
+    m_table->PutNumber(kP, GetP());
+    m_table->PutNumber(kI, GetI());
+    m_table->PutNumber(kD, GetD());
+    m_table->PutNumber(kF, GetF());
+    m_table->PutNumber(kSetpoint, GetSetpoint());
+    m_table->PutBoolean(kEnabled, IsEnabled());
+    m_table->AddTableListener(this, false);
+  }
+}
+
+/**
+ * Wraps error around for continuous inputs. The original error is returned if
+ * continuous mode is disabled. This is an unsynchronized function.
+ *
+ * @param error The current error of the PID controller.
+ * @return Error for continuous inputs.
+ */
+double PIDController::GetContinuousError(double error) const {
+  if (m_continuous) {
+    if (std::fabs(error) > (m_maximumInput - m_minimumInput) / 2) {
+      if (error > 0) {
+        return error - (m_maximumInput - m_minimumInput);
+      } else {
+        return error + (m_maximumInput - m_minimumInput);
+      }
+    }
+  }
+
+  return error;
+}
+
+std::shared_ptr<ITable> PIDController::GetTable() const { return m_table; }
+
+void PIDController::ValueChanged(ITable* source, llvm::StringRef key,
+                                 std::shared_ptr<nt::Value> value, bool isNew) {
+  if (key == kP || key == kI || key == kD || key == kF) {
+    if (m_P != m_table->GetNumber(kP, 0.0) ||
+        m_I != m_table->GetNumber(kI, 0.0) ||
+        m_D != m_table->GetNumber(kD, 0.0) ||
+        m_F != m_table->GetNumber(kF, 0.0)) {
+      SetPID(m_table->GetNumber(kP, 0.0), m_table->GetNumber(kI, 0.0),
+             m_table->GetNumber(kD, 0.0), m_table->GetNumber(kF, 0.0));
+    }
+  } else if (key == kSetpoint && value->IsDouble() &&
+             m_setpoint != value->GetDouble()) {
+    SetSetpoint(value->GetDouble());
+  } else if (key == kEnabled && value->IsBoolean() &&
+             m_enabled != value->GetBoolean()) {
+    if (value->GetBoolean()) {
+      Enable();
+    } else {
+      Disable();
+    }
+  }
+}
+
+void PIDController::UpdateTable() {}
+
+void PIDController::StartLiveWindowMode() { Disable(); }
+
+void PIDController::StopLiveWindowMode() {}
diff --git a/wpilibc/athena/src/PWM.cpp b/wpilibc/athena/src/PWM.cpp
new file mode 100644
index 0000000..4883e16
--- /dev/null
+++ b/wpilibc/athena/src/PWM.cpp
@@ -0,0 +1,348 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "PWM.h"
+
+#include <sstream>
+
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * 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) {
+  std::stringstream buf;
+
+  if (!CheckPWMChannel(channel)) {
+    buf << "PWM Channel " << channel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    return;
+  }
+
+  int32_t status = 0;
+  m_handle = HAL_InitializePWMPort(HAL_GetPort(channel), &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumPWMChannels(), channel,
+                                 HAL_GetErrorMessage(status));
+    m_channel = std::numeric_limits<int>::max();
+    m_handle = HAL_kInvalidHandle;
+    return;
+  }
+
+  m_channel = channel;
+
+  HAL_SetPWMDisabled(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  status = 0;
+  HAL_SetPWMEliminateDeadband(m_handle, false, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  HAL_Report(HALUsageReporting::kResourceType_PWM, channel);
+}
+
+/**
+ * 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);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  HAL_FreePWMPort(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+}
+
+/**
+ * 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) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMEliminateDeadband(m_handle, eliminateDeadband, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * 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) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMConfig(m_handle, max, deadbandMax, center, deadbandMin, min,
+                   &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * 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) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min,
+                      &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * 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);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * 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) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMPosition(m_handle, pos, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * 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 {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double position = HAL_GetPWMPosition(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  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) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMSpeed(m_handle, speed, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * 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 {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double speed = HAL_GetPWMSpeed(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  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) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_SetPWMRaw(m_handle, value, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * 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 {
+  if (StatusIsFatal()) return 0;
+
+  int32_t status = 0;
+  uint16_t value = HAL_GetPWMRaw(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  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) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  switch (mult) {
+    case kPeriodMultiplier_4X:
+      HAL_SetPWMPeriodScale(m_handle, 3,
+                            &status);  // Squelch 3 out of 4 outputs
+      break;
+    case kPeriodMultiplier_2X:
+      HAL_SetPWMPeriodScale(m_handle, 1,
+                            &status);  // Squelch 1 out of 2 outputs
+      break;
+    case kPeriodMultiplier_1X:
+      HAL_SetPWMPeriodScale(m_handle, 0, &status);  // Don't squelch any outputs
+      break;
+    default:
+      wpi_assert(false);
+  }
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Temporarily disables the PWM output. The next set call will reenable
+ * the output.
+ */
+void PWM::SetDisabled() {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  HAL_SetPWMDisabled(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void PWM::SetZeroLatch() {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  HAL_LatchPWMZero(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void PWM::ValueChanged(ITable* source, llvm::StringRef key,
+                       std::shared_ptr<nt::Value> value, bool isNew) {
+  if (!value->IsDouble()) return;
+  SetSpeed(value->GetDouble());
+}
+
+void PWM::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", GetSpeed());
+  }
+}
+
+void PWM::StartLiveWindowMode() {
+  SetSpeed(0);
+  if (m_table != nullptr) {
+    m_table->AddTableListener("Value", this, true);
+  }
+}
+
+void PWM::StopLiveWindowMode() {
+  SetSpeed(0);
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+std::string PWM::GetSmartDashboardType() const { return "Speed Controller"; }
+
+void PWM::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> PWM::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/PWMSpeedController.cpp b/wpilibc/athena/src/PWMSpeedController.cpp
new file mode 100644
index 0000000..6c5ed5a
--- /dev/null
+++ b/wpilibc/athena/src/PWMSpeedController.cpp
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "PWMSpeedController.h"
+
+using namespace frc;
+
+/**
+ * Constructor for a PWM Speed Controller connected via PWM.
+ *
+ * @param channel The PWM channel that the controller is attached to. 0-9 are
+ *                on-board, 10-19 are on the MXP port
+ */
+PWMSpeedController::PWMSpeedController(int channel) : SafePWM(channel) {}
+
+/**
+ * Set the PWM value.
+ *
+ * The PWM value is set using a range of -1.0 to 1.0, appropriately
+ * scaling the value for the FPGA.
+ *
+ * @param speed The speed value between -1.0 and 1.0 to set.
+ */
+void PWMSpeedController::Set(double speed) {
+  SetSpeed(m_isInverted ? -speed : speed);
+}
+
+/**
+ * Get the recently set value of the PWM.
+ *
+ * @return The most recently set value for the PWM between -1.0 and 1.0.
+ */
+double PWMSpeedController::Get() const { return GetSpeed(); }
+
+/**
+ * Common interface for disabling a motor.
+ */
+void PWMSpeedController::Disable() { SetDisabled(); }
+
+/**
+ * Common interface for inverting direction of a speed controller.
+ *
+ * @param isInverted The state of inversion, true is inverted.
+ */
+void PWMSpeedController::SetInverted(bool isInverted) {
+  m_isInverted = isInverted;
+}
+
+/**
+ * Common interface for the inverting direction of a speed controller.
+ *
+ * @return isInverted The state of inversion, true is inverted.
+ *
+ */
+bool PWMSpeedController::GetInverted() const { return m_isInverted; }
+
+/**
+ * Write out the PID value as seen in the PIDOutput base object.
+ *
+ * @param output Write out the PWM value as was found in the PIDController
+ */
+void PWMSpeedController::PIDWrite(double output) { Set(output); }
+
+/**
+ * Common interface to stop the motor until Set is called again.
+ */
+void PWMSpeedController::StopMotor() { this->SafePWM::StopMotor(); }
diff --git a/wpilibc/athena/src/PowerDistributionPanel.cpp b/wpilibc/athena/src/PowerDistributionPanel.cpp
new file mode 100644
index 0000000..870c92e
--- /dev/null
+++ b/wpilibc/athena/src/PowerDistributionPanel.cpp
@@ -0,0 +1,218 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "PowerDistributionPanel.h"
+
+#include <sstream>
+
+#include "HAL/HAL.h"
+#include "HAL/PDP.h"
+#include "HAL/Ports.h"
+#include "LiveWindow/LiveWindow.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+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 {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+
+  double voltage = HAL_GetPDPVoltage(m_module, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return voltage;
+}
+
+/**
+ * Query the temperature of the PDP.
+ *
+ * @return The temperature of the PDP in degrees Celsius
+ */
+double PowerDistributionPanel::GetTemperature() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+
+  double temperature = HAL_GetPDPTemperature(m_module, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(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 {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+
+  if (!CheckPDPChannel(channel)) {
+    std::stringstream buf;
+    buf << "PDP Channel " << channel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+  }
+
+  double current = HAL_GetPDPChannelCurrent(m_module, channel, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(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 {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+
+  double current = HAL_GetPDPTotalCurrent(m_module, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(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 {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+
+  double power = HAL_GetPDPTotalPower(m_module, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(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 {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+
+  double energy = HAL_GetPDPTotalEnergy(m_module, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return energy;
+}
+
+/**
+ * Reset the total energy drawn from the PDP.
+ *
+ * @see PowerDistributionPanel#GetTotalEnergy
+ */
+void PowerDistributionPanel::ResetTotalEnergy() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+
+  HAL_ResetPDPTotalEnergy(m_module, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+}
+
+/**
+ * Remove all of the fault flags on the PDP.
+ */
+void PowerDistributionPanel::ClearStickyFaults() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+
+  HAL_ClearPDPStickyFaults(m_module, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+}
+
+void PowerDistributionPanel::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Chan0", GetCurrent(0));
+    m_table->PutNumber("Chan1", GetCurrent(1));
+    m_table->PutNumber("Chan2", GetCurrent(2));
+    m_table->PutNumber("Chan3", GetCurrent(3));
+    m_table->PutNumber("Chan4", GetCurrent(4));
+    m_table->PutNumber("Chan5", GetCurrent(5));
+    m_table->PutNumber("Chan6", GetCurrent(6));
+    m_table->PutNumber("Chan7", GetCurrent(7));
+    m_table->PutNumber("Chan8", GetCurrent(8));
+    m_table->PutNumber("Chan9", GetCurrent(9));
+    m_table->PutNumber("Chan10", GetCurrent(10));
+    m_table->PutNumber("Chan11", GetCurrent(11));
+    m_table->PutNumber("Chan12", GetCurrent(12));
+    m_table->PutNumber("Chan13", GetCurrent(13));
+    m_table->PutNumber("Chan14", GetCurrent(14));
+    m_table->PutNumber("Chan15", GetCurrent(15));
+    m_table->PutNumber("Voltage", GetVoltage());
+    m_table->PutNumber("TotalCurrent", GetTotalCurrent());
+  }
+}
+
+void PowerDistributionPanel::StartLiveWindowMode() {}
+
+void PowerDistributionPanel::StopLiveWindowMode() {}
+
+std::string PowerDistributionPanel::GetSmartDashboardType() const {
+  return "PowerDistributionPanel";
+}
+
+void PowerDistributionPanel::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> PowerDistributionPanel::GetTable() const {
+  return m_table;
+}
diff --git a/wpilibc/athena/src/Preferences.cpp b/wpilibc/athena/src/Preferences.cpp
new file mode 100644
index 0000000..a913ba0
--- /dev/null
+++ b/wpilibc/athena/src/Preferences.cpp
@@ -0,0 +1,227 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Preferences.h"
+
+#include <algorithm>
+
+#include "HAL/HAL.h"
+#include "WPIErrors.h"
+#include "llvm/StringRef.h"
+
+using namespace frc;
+
+/** The Preferences table name */
+static llvm::StringRef kTableName{"Preferences"};
+
+void Preferences::Listener::ValueChanged(ITable* source, llvm::StringRef key,
+                                         std::shared_ptr<nt::Value> value,
+                                         bool isNew) {}
+void Preferences::Listener::ValueChangedEx(ITable* source, llvm::StringRef key,
+                                           std::shared_ptr<nt::Value> value,
+                                           uint32_t flags) {
+  source->SetPersistent(key);
+}
+
+Preferences::Preferences() : m_table(NetworkTable::GetTable(kTableName)) {
+  m_table->AddTableListenerEx(&m_listener, NT_NOTIFY_NEW | NT_NOTIFY_IMMEDIATE);
+  HAL_Report(HALUsageReporting::kResourceType_Preferences, 0);
+}
+
+/**
+ * Get the one and only {@link Preferences} object.
+ *
+ * @return pointer to the {@link Preferences}
+ */
+Preferences* Preferences::GetInstance() {
+  static Preferences instance;
+  return &instance;
+}
+
+/**
+ * Returns a vector of all the keys.
+ *
+ * @return a vector of the keys
+ */
+std::vector<std::string> Preferences::GetKeys() { return m_table->GetKeys(); }
+
+/**
+ * Returns the string at the given key.  If this table does not have a value
+ * for that position, then the given defaultValue will be returned.
+ *
+ * @param key          the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+std::string Preferences::GetString(llvm::StringRef key,
+                                   llvm::StringRef defaultValue) {
+  return m_table->GetString(key, defaultValue);
+}
+
+/**
+ * Returns the int at the given key.  If this table does not have a value for
+ * that position, then the given defaultValue value will be returned.
+ *
+ * @param key          the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+int Preferences::GetInt(llvm::StringRef key, int defaultValue) {
+  return static_cast<int>(m_table->GetNumber(key, defaultValue));
+}
+
+/**
+ * Returns the double at the given key.  If this table does not have a value
+ * for that position, then the given defaultValue value will be returned.
+ *
+ * @param key          the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+double Preferences::GetDouble(llvm::StringRef key, double defaultValue) {
+  return m_table->GetNumber(key, defaultValue);
+}
+
+/**
+ * Returns the float at the given key.  If this table does not have a value
+ * for that position, then the given defaultValue value will be returned.
+ *
+ * @param key          the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+float Preferences::GetFloat(llvm::StringRef key, float defaultValue) {
+  return m_table->GetNumber(key, defaultValue);
+}
+
+/**
+ * Returns the boolean at the given key.  If this table does not have a value
+ * for that position, then the given defaultValue value will be returned.
+ *
+ * @param key          the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+bool Preferences::GetBoolean(llvm::StringRef key, bool defaultValue) {
+  return m_table->GetBoolean(key, defaultValue);
+}
+
+/**
+ * Returns the long (int64_t) at the given key.  If this table does not have a
+ * value for that position, then the given defaultValue value will be returned.
+ *
+ * @param key          the key
+ * @param defaultValue the value to return if none exists in the table
+ * @return either the value in the table, or the defaultValue
+ */
+int64_t Preferences::GetLong(llvm::StringRef key, int64_t defaultValue) {
+  return static_cast<int64_t>(m_table->GetNumber(key, defaultValue));
+}
+
+/**
+ * Puts the given string into the preferences table.
+ *
+ * <p>The value may not have quotation marks, nor may the key
+ * have any whitespace nor an equals sign</p>
+ *
+ * @param key   the key
+ * @param value the value
+ */
+void Preferences::PutString(llvm::StringRef key, llvm::StringRef value) {
+  m_table->PutString(key, value);
+  m_table->SetPersistent(key);
+}
+
+/**
+ * Puts the given int into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * @param key   the key
+ * @param value the value
+ */
+void Preferences::PutInt(llvm::StringRef key, int value) {
+  m_table->PutNumber(key, value);
+  m_table->SetPersistent(key);
+}
+
+/**
+ * Puts the given double into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * @param key   the key
+ * @param value the value
+ */
+void Preferences::PutDouble(llvm::StringRef key, double value) {
+  m_table->PutNumber(key, value);
+  m_table->SetPersistent(key);
+}
+
+/**
+ * Puts the given float into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * @param key   the key
+ * @param value the value
+ */
+void Preferences::PutFloat(llvm::StringRef key, float value) {
+  m_table->PutNumber(key, value);
+  m_table->SetPersistent(key);
+}
+
+/**
+ * Puts the given boolean into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * @param key   the key
+ * @param value the value
+ */
+void Preferences::PutBoolean(llvm::StringRef key, bool value) {
+  m_table->PutBoolean(key, value);
+  m_table->SetPersistent(key);
+}
+
+/**
+ * Puts the given long (int64_t) into the preferences table.
+ *
+ * <p>The key may not have any whitespace nor an equals sign</p>
+ *
+ * @param key   the key
+ * @param value the value
+ */
+void Preferences::PutLong(llvm::StringRef key, int64_t value) {
+  m_table->PutNumber(key, value);
+  m_table->SetPersistent(key);
+}
+
+/**
+ * This function is no longer required, as NetworkTables automatically
+ * saves persistent values (which all Preferences values are) periodically
+ * when running as a server.
+ * @deprecated backwards compatibility shim
+ */
+void Preferences::Save() {}
+
+/**
+ * Returns whether or not there is a key with the given name.
+ *
+ * @param key the key
+ * @return if there is a value at the given key
+ */
+bool Preferences::ContainsKey(llvm::StringRef key) {
+  return m_table->ContainsKey(key);
+}
+
+/**
+ * Remove a preference.
+ *
+ * @param key the key
+ */
+void Preferences::Remove(llvm::StringRef key) { m_table->Delete(key); }
diff --git a/wpilibc/athena/src/Relay.cpp b/wpilibc/athena/src/Relay.cpp
new file mode 100644
index 0000000..33cc876
--- /dev/null
+++ b/wpilibc/athena/src/Relay.cpp
@@ -0,0 +1,315 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Relay.h"
+
+#include <sstream>
+
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "LiveWindow/LiveWindow.h"
+#include "MotorSafetyHelper.h"
+#include "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 (!SensorBase::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;
+    }
+  }
+
+  m_safetyHelper = std::make_unique<MotorSafetyHelper>(this);
+  m_safetyHelper->SetSafetyEnabled(false);
+
+  LiveWindow::GetInstance()->AddActuator("Relay", 1, m_channel, this);
+}
+
+/**
+ * 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);
+
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+}
+
+/**
+ * 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; }
+
+/**
+ * Set the expiration time for the Relay object
+ * @param timeout The timeout (in seconds) for this relay object
+ */
+void Relay::SetExpiration(double timeout) {
+  m_safetyHelper->SetExpiration(timeout);
+}
+
+/**
+ * Return the expiration time for the relay object.
+ * @return The expiration time value.
+ */
+double Relay::GetExpiration() const { return m_safetyHelper->GetExpiration(); }
+
+/**
+ * Check if the relay object is currently alive or stopped due to a timeout.
+ *
+ * @return a bool value that is true if the motor has NOT timed out and should
+ *         still be running.
+ */
+bool Relay::IsAlive() const { return m_safetyHelper->IsAlive(); }
+
+/**
+ * Stop the motor associated with this PWM object.
+ *
+ * This is called by the MotorSafetyHelper object when it has a timeout for this
+ * relay and needs to stop it from running.
+ */
+void Relay::StopMotor() { Set(kOff); }
+
+/**
+ * Enable/disable motor safety for this device.
+ *
+ * Turn on and off the motor safety option for this relay object.
+ *
+ * @param enabled True if motor safety is enforced for this object
+ */
+void Relay::SetSafetyEnabled(bool enabled) {
+  m_safetyHelper->SetSafetyEnabled(enabled);
+}
+
+/**
+ * Check if motor safety is enabled for this object.
+ *
+ * @returns True if motor safety is enforced for this object
+ */
+bool Relay::IsSafetyEnabled() const {
+  return m_safetyHelper->IsSafetyEnabled();
+}
+
+void Relay::GetDescription(std::ostringstream& desc) const {
+  desc << "Relay " << GetChannel();
+}
+
+void Relay::ValueChanged(ITable* source, llvm::StringRef key,
+                         std::shared_ptr<nt::Value> value, bool isNew) {
+  if (!value->IsString()) return;
+  if (value->GetString() == "Off")
+    Set(kOff);
+  else if (value->GetString() == "Forward")
+    Set(kForward);
+  else if (value->GetString() == "Reverse")
+    Set(kReverse);
+  else if (value->GetString() == "On")
+    Set(kOn);
+}
+
+void Relay::UpdateTable() {
+  if (m_table != nullptr) {
+    if (Get() == kOn) {
+      m_table->PutString("Value", "On");
+    } else if (Get() == kForward) {
+      m_table->PutString("Value", "Forward");
+    } else if (Get() == kReverse) {
+      m_table->PutString("Value", "Reverse");
+    } else {
+      m_table->PutString("Value", "Off");
+    }
+  }
+}
+
+void Relay::StartLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->AddTableListener("Value", this, true);
+  }
+}
+
+void Relay::StopLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+std::string Relay::GetSmartDashboardType() const { return "Relay"; }
+
+void Relay::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> Relay::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/RobotBase.cpp b/wpilibc/athena/src/RobotBase.cpp
new file mode 100644
index 0000000..e242d03
--- /dev/null
+++ b/wpilibc/athena/src/RobotBase.cpp
@@ -0,0 +1,101 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "RobotBase.h"
+
+#include <cstdio>
+
+#include "DriverStation.h"
+#include "HAL/HAL.h"
+#include "HLUsageReporting.h"
+#include "Internal/HardwareHLReporting.h"
+#include "RobotState.h"
+#include "SmartDashboard/SmartDashboard.h"
+#include "Utility.h"
+#include "WPILibVersion.h"
+#include "networktables/NetworkTable.h"
+
+using namespace frc;
+
+std::thread::id RobotBase::m_threadId;
+
+/**
+ * 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()) {
+  m_threadId = std::this_thread::get_id();
+
+  RobotState::SetImplementation(DriverStation::GetInstance());
+  HLUsageReporting::SetImplementation(new HardwareHLReporting());
+
+  NetworkTable::SetNetworkIdentity("Robot");
+  NetworkTable::SetPersistentFilename("/home/lvuser/networktables.ini");
+
+  SmartDashboard::init();
+
+  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);
+  }
+}
+
+/**
+ * Determine if the Robot is currently enabled.
+ * @return True if the Robot is currently enabled by the field controls.
+ */
+bool RobotBase::IsEnabled() const { return m_ds.IsEnabled(); }
+
+/**
+ * Determine if the Robot is currently disabled.
+ * @return True if the Robot is currently disabled by the field controls.
+ */
+bool RobotBase::IsDisabled() const { return m_ds.IsDisabled(); }
+
+/**
+ * Determine if the robot is currently in Autonomous mode.
+ * @return True if the robot is currently operating Autonomously as determined
+ * by the field controls.
+ */
+bool RobotBase::IsAutonomous() const { return m_ds.IsAutonomous(); }
+
+/**
+ * Determine if the robot is currently in Operator Control mode.
+ * @return True if the robot is currently operating in Tele-Op mode as
+ * determined by the field controls.
+ */
+bool RobotBase::IsOperatorControl() const { return m_ds.IsOperatorControl(); }
+
+/**
+ * Determine if the robot is currently in Test mode.
+ * @return True if the robot is currently running tests as determined by the
+ * field controls.
+ */
+bool RobotBase::IsTest() const { return m_ds.IsTest(); }
+
+/**
+ * Indicates if new data is available from the driver station.
+ * @return Has new data arrived over the network since the last time this
+ * function was called?
+ */
+bool RobotBase::IsNewDataAvailable() const { return m_ds.IsNewControlData(); }
+
+/**
+ * Gets the ID of the main robot thread
+ */
+std::thread::id RobotBase::GetThreadId() { return m_threadId; }
diff --git a/wpilibc/athena/src/RobotDrive.cpp b/wpilibc/athena/src/RobotDrive.cpp
new file mode 100644
index 0000000..c8c1897
--- /dev/null
+++ b/wpilibc/athena/src/RobotDrive.cpp
@@ -0,0 +1,747 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "RobotDrive.h"
+
+#include <algorithm>
+#include <cmath>
+
+#include "GenericHID.h"
+#include "HAL/HAL.h"
+#include "Joystick.h"
+#include "Talon.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+const int RobotDrive::kMaxNumberOfMotors;
+
+static auto make_shared_nodelete(SpeedController* ptr) {
+  return std::shared_ptr<SpeedController>(ptr, NullDeleter<SpeedController>());
+}
+
+/*
+ * Driving functions
+ * These functions provide an interface to multiple motors that is used for C
+ * programming.
+ * The Drive(speed, direction) function is the main part of the set that makes
+ * it easy to set speeds and direction independently in one call.
+ */
+
+/**
+ * Common function to initialize all the robot drive constructors.
+ *
+ * Create a motor safety object (the real reason for the common code) and
+ * initialize all the motor assignments. The default timeout is set for the
+ * robot drive.
+ */
+void RobotDrive::InitRobotDrive() {
+  m_safetyHelper = std::make_unique<MotorSafetyHelper>(this);
+  m_safetyHelper->SetSafetyEnabled(true);
+}
+
+/**
+ * Constructor for RobotDrive with 2 motors specified with channel numbers.
+ *
+ * Set up parameters for a two wheel drive system where the
+ * left and right motor pwm channels are specified in the call.
+ * This call assumes Talons for controlling the motors.
+ *
+ * @param leftMotorChannel  The PWM channel number that drives the left motor.
+ *                          0-9 are on-board, 10-19 are on the MXP port
+ * @param rightMotorChannel The PWM channel number that drives the right motor.
+ *                          0-9 are on-board, 10-19 are on the MXP port
+ */
+RobotDrive::RobotDrive(int leftMotorChannel, int rightMotorChannel) {
+  InitRobotDrive();
+  m_rearLeftMotor = std::make_shared<Talon>(leftMotorChannel);
+  m_rearRightMotor = std::make_shared<Talon>(rightMotorChannel);
+  SetLeftRightMotorOutputs(0.0, 0.0);
+}
+
+/**
+ * Constructor for RobotDrive with 4 motors specified with channel numbers.
+ *
+ * Set up parameters for a four wheel drive system where all four motor
+ * pwm channels are specified in the call.
+ * This call assumes Talons for controlling the motors.
+ *
+ * @param frontLeftMotor  Front left motor channel number. 0-9 are on-board,
+ *                        10-19 are on the MXP port
+ * @param rearLeftMotor   Rear Left motor channel number. 0-9 are on-board,
+ *                        10-19 are on the MXP port
+ * @param frontRightMotor Front right motor channel number. 0-9 are on-board,
+ *                        10-19 are on the MXP port
+ * @param rearRightMotor  Rear Right motor channel number. 0-9 are on-board,
+ *                        10-19 are on the MXP port
+ */
+RobotDrive::RobotDrive(int frontLeftMotor, int rearLeftMotor,
+                       int frontRightMotor, int rearRightMotor) {
+  InitRobotDrive();
+  m_rearLeftMotor = std::make_shared<Talon>(rearLeftMotor);
+  m_rearRightMotor = std::make_shared<Talon>(rearRightMotor);
+  m_frontLeftMotor = std::make_shared<Talon>(frontLeftMotor);
+  m_frontRightMotor = std::make_shared<Talon>(frontRightMotor);
+  SetLeftRightMotorOutputs(0.0, 0.0);
+}
+
+/**
+ * Constructor for RobotDrive with 2 motors specified as SpeedController
+ * objects.
+ *
+ * The SpeedController version of the constructor enables programs to use the
+ * RobotDrive classes with subclasses of the SpeedController objects, for
+ * example, versions with ramping or reshaping of the curve to suit motor bias
+ * or deadband elimination.
+ *
+ * @param leftMotor  The left SpeedController object used to drive the robot.
+ * @param rightMotor The right SpeedController object used to drive the robot.
+ */
+RobotDrive::RobotDrive(SpeedController* leftMotor,
+                       SpeedController* rightMotor) {
+  InitRobotDrive();
+  if (leftMotor == nullptr || rightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    m_rearLeftMotor = m_rearRightMotor = nullptr;
+    return;
+  }
+  m_rearLeftMotor = make_shared_nodelete(leftMotor);
+  m_rearRightMotor = make_shared_nodelete(rightMotor);
+}
+
+// TODO: Change to rvalue references & move syntax.
+RobotDrive::RobotDrive(SpeedController& leftMotor,
+                       SpeedController& rightMotor) {
+  InitRobotDrive();
+  m_rearLeftMotor = make_shared_nodelete(&leftMotor);
+  m_rearRightMotor = make_shared_nodelete(&rightMotor);
+}
+
+RobotDrive::RobotDrive(std::shared_ptr<SpeedController> leftMotor,
+                       std::shared_ptr<SpeedController> rightMotor) {
+  InitRobotDrive();
+  if (leftMotor == nullptr || rightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    m_rearLeftMotor = m_rearRightMotor = nullptr;
+    return;
+  }
+  m_rearLeftMotor = leftMotor;
+  m_rearRightMotor = rightMotor;
+}
+
+/**
+ * Constructor for RobotDrive with 4 motors specified as SpeedController
+ * objects.
+ *
+ * Speed controller input version of RobotDrive (see previous comments).
+ *
+ * @param rearLeftMotor   The back left SpeedController object used to drive
+ *                        the robot.
+ * @param frontLeftMotor  The front left SpeedController object used to drive
+ *                        the robot.
+ * @param rearRightMotor  The back right SpeedController object used to drive
+ *                        the robot.
+ * @param frontRightMotor The front right SpeedController object used to drive
+ *                        the robot.
+ */
+RobotDrive::RobotDrive(SpeedController* frontLeftMotor,
+                       SpeedController* rearLeftMotor,
+                       SpeedController* frontRightMotor,
+                       SpeedController* rearRightMotor) {
+  InitRobotDrive();
+  if (frontLeftMotor == nullptr || rearLeftMotor == nullptr ||
+      frontRightMotor == nullptr || rearRightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  m_frontLeftMotor = make_shared_nodelete(frontLeftMotor);
+  m_rearLeftMotor = make_shared_nodelete(rearLeftMotor);
+  m_frontRightMotor = make_shared_nodelete(frontRightMotor);
+  m_rearRightMotor = make_shared_nodelete(rearRightMotor);
+}
+
+RobotDrive::RobotDrive(SpeedController& frontLeftMotor,
+                       SpeedController& rearLeftMotor,
+                       SpeedController& frontRightMotor,
+                       SpeedController& rearRightMotor) {
+  InitRobotDrive();
+  m_frontLeftMotor = make_shared_nodelete(&frontLeftMotor);
+  m_rearLeftMotor = make_shared_nodelete(&rearLeftMotor);
+  m_frontRightMotor = make_shared_nodelete(&frontRightMotor);
+  m_rearRightMotor = make_shared_nodelete(&rearRightMotor);
+}
+
+RobotDrive::RobotDrive(std::shared_ptr<SpeedController> frontLeftMotor,
+                       std::shared_ptr<SpeedController> rearLeftMotor,
+                       std::shared_ptr<SpeedController> frontRightMotor,
+                       std::shared_ptr<SpeedController> rearRightMotor) {
+  InitRobotDrive();
+  if (frontLeftMotor == nullptr || rearLeftMotor == nullptr ||
+      frontRightMotor == nullptr || rearRightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  m_frontLeftMotor = frontLeftMotor;
+  m_rearLeftMotor = rearLeftMotor;
+  m_frontRightMotor = frontRightMotor;
+  m_rearRightMotor = rearRightMotor;
+}
+
+/**
+ * Drive the motors at "outputMagnitude" and "curve".
+ * Both outputMagnitude and curve are -1.0 to +1.0 values, where 0.0 represents
+ * stopped and not turning. curve < 0 will turn left and curve > 0 will turn
+ * right.
+ *
+ * The algorithm for steering provides a constant turn radius for any normal
+ * speed range, both forward and backward. Increasing m_sensitivity causes
+ * sharper turns for fixed values of curve.
+ *
+ * This function will most likely be used in an autonomous routine.
+ *
+ * @param outputMagnitude The speed setting for the outside wheel in a turn,
+ *                        forward or backwards, +1 to -1.
+ * @param curve           The rate of turn, constant for different forward
+ *                        speeds. Set curve < 0 for left turn or curve > 0 for
+ *                        right turn.
+ *
+ * Set curve = e^(-r/w) to get a turn radius r for wheelbase w of your robot.
+ * Conversely, turn radius r = -ln(curve)*w for a given value of curve and
+ * wheelbase w.
+ */
+void RobotDrive::Drive(double outputMagnitude, double curve) {
+  double leftOutput, rightOutput;
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+               HALUsageReporting::kRobotDrive_ArcadeRatioCurve);
+    reported = true;
+  }
+
+  if (curve < 0) {
+    double value = std::log(-curve);
+    double ratio = (value - m_sensitivity) / (value + m_sensitivity);
+    if (ratio == 0) ratio = .0000000001;
+    leftOutput = outputMagnitude / ratio;
+    rightOutput = outputMagnitude;
+  } else if (curve > 0) {
+    double value = std::log(curve);
+    double ratio = (value - m_sensitivity) / (value + m_sensitivity);
+    if (ratio == 0) ratio = .0000000001;
+    leftOutput = outputMagnitude;
+    rightOutput = outputMagnitude / ratio;
+  } else {
+    leftOutput = outputMagnitude;
+    rightOutput = outputMagnitude;
+  }
+  SetLeftRightMotorOutputs(leftOutput, rightOutput);
+}
+
+/**
+ * Provide tank steering using the stored robot configuration.
+ *
+ * Drive the robot using two joystick inputs. The Y-axis will be selected from
+ * each Joystick object.
+ *
+ * @param leftStick  The joystick to control the left side of the robot.
+ * @param rightStick The joystick to control the right side of the robot.
+ */
+void RobotDrive::TankDrive(GenericHID* leftStick, GenericHID* rightStick,
+                           bool squaredInputs) {
+  if (leftStick == nullptr || rightStick == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  TankDrive(leftStick->GetY(), rightStick->GetY(), squaredInputs);
+}
+
+void RobotDrive::TankDrive(GenericHID& leftStick, GenericHID& rightStick,
+                           bool squaredInputs) {
+  TankDrive(leftStick.GetY(), rightStick.GetY(), squaredInputs);
+}
+
+/**
+ * Provide tank steering using the stored robot configuration.
+ *
+ * This function lets you pick the axis to be used on each Joystick object for
+ * the left and right sides of the robot.
+ *
+ * @param leftStick  The Joystick object to use for the left side of the robot.
+ * @param leftAxis   The axis to select on the left side Joystick object.
+ * @param rightStick The Joystick object to use for the right side of the
+ *                   robot.
+ * @param rightAxis  The axis to select on the right side Joystick object.
+ */
+void RobotDrive::TankDrive(GenericHID* leftStick, int leftAxis,
+                           GenericHID* rightStick, int rightAxis,
+                           bool squaredInputs) {
+  if (leftStick == nullptr || rightStick == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  TankDrive(leftStick->GetRawAxis(leftAxis), rightStick->GetRawAxis(rightAxis),
+            squaredInputs);
+}
+
+void RobotDrive::TankDrive(GenericHID& leftStick, int leftAxis,
+                           GenericHID& rightStick, int rightAxis,
+                           bool squaredInputs) {
+  TankDrive(leftStick.GetRawAxis(leftAxis), rightStick.GetRawAxis(rightAxis),
+            squaredInputs);
+}
+
+/**
+ * Provide tank steering using the stored robot configuration.
+ *
+ * This function lets you directly provide joystick values from any source.
+ *
+ * @param leftValue  The value of the left stick.
+ * @param rightValue The value of the right stick.
+ */
+void RobotDrive::TankDrive(double leftValue, double rightValue,
+                           bool squaredInputs) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+               HALUsageReporting::kRobotDrive_Tank);
+    reported = true;
+  }
+
+  // square the inputs (while preserving the sign) to increase fine control
+  // while permitting full power
+  leftValue = Limit(leftValue);
+  rightValue = Limit(rightValue);
+  if (squaredInputs) {
+    if (leftValue >= 0.0) {
+      leftValue = (leftValue * leftValue);
+    } else {
+      leftValue = -(leftValue * leftValue);
+    }
+    if (rightValue >= 0.0) {
+      rightValue = (rightValue * rightValue);
+    } else {
+      rightValue = -(rightValue * rightValue);
+    }
+  }
+
+  SetLeftRightMotorOutputs(leftValue, rightValue);
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ *
+ * Given a single Joystick, the class assumes the Y axis for the move value and
+ * the X axis for the rotate value.
+ * (Should add more information here regarding the way that arcade drive works.)
+ *
+ * @param stick         The joystick to use for Arcade single-stick driving.
+ *                      The Y-axis will be selected for forwards/backwards and
+ *                      the X-axis will be selected for rotation rate.
+ * @param squaredInputs If true, the sensitivity will be increased for small
+ *                      values
+ */
+void RobotDrive::ArcadeDrive(GenericHID* stick, bool squaredInputs) {
+  // simply call the full-featured ArcadeDrive with the appropriate values
+  ArcadeDrive(stick->GetY(), stick->GetX(), squaredInputs);
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ *
+ * Given a single Joystick, the class assumes the Y axis for the move value and
+ * the X axis for the rotate value.
+ * (Should add more information here regarding the way that arcade drive works.)
+ *
+ * @param stick         The joystick to use for Arcade single-stick driving.
+ *                      The Y-axis will be selected for forwards/backwards and
+ *                      the X-axis will be selected for rotation rate.
+ * @param squaredInputs If true, the sensitivity will be increased for small
+ *                      values
+ */
+void RobotDrive::ArcadeDrive(GenericHID& stick, bool squaredInputs) {
+  // simply call the full-featured ArcadeDrive with the appropriate values
+  ArcadeDrive(stick.GetY(), stick.GetX(), squaredInputs);
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ *
+ * Given two joystick instances and two axis, compute the values to send to
+ * either two or four motors.
+ *
+ * @param moveStick     The Joystick object that represents the
+ *                      forward/backward direction
+ * @param moveAxis      The axis on the moveStick object to use for
+ *                      forwards/backwards (typically Y_AXIS)
+ * @param rotateStick   The Joystick object that represents the rotation value
+ * @param rotateAxis    The axis on the rotation object to use for the rotate
+ *                      right/left (typically X_AXIS)
+ * @param squaredInputs Setting this parameter to true increases the
+ *                      sensitivity at lower speeds
+ */
+void RobotDrive::ArcadeDrive(GenericHID* moveStick, int moveAxis,
+                             GenericHID* rotateStick, int rotateAxis,
+                             bool squaredInputs) {
+  double moveValue = moveStick->GetRawAxis(moveAxis);
+  double rotateValue = rotateStick->GetRawAxis(rotateAxis);
+
+  ArcadeDrive(moveValue, rotateValue, squaredInputs);
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ *
+ * Given two joystick instances and two axis, compute the values to send to
+ * either two or four motors.
+ *
+ * @param moveStick     The Joystick object that represents the
+ *                      forward/backward direction
+ * @param moveAxis      The axis on the moveStick object to use for
+ *                      forwards/backwards (typically Y_AXIS)
+ * @param rotateStick   The Joystick object that represents the rotation value
+ * @param rotateAxis    The axis on the rotation object to use for the rotate
+ *                      right/left (typically X_AXIS)
+ * @param squaredInputs Setting this parameter to true increases the
+ *                      sensitivity at lower speeds
+ */
+void RobotDrive::ArcadeDrive(GenericHID& moveStick, int moveAxis,
+                             GenericHID& rotateStick, int rotateAxis,
+                             bool squaredInputs) {
+  double moveValue = moveStick.GetRawAxis(moveAxis);
+  double rotateValue = rotateStick.GetRawAxis(rotateAxis);
+
+  ArcadeDrive(moveValue, rotateValue, squaredInputs);
+}
+
+/**
+ * Arcade drive implements single stick driving.
+ *
+ * This function lets you directly provide joystick values from any source.
+ *
+ * @param moveValue     The value to use for fowards/backwards
+ * @param rotateValue   The value to use for the rotate right/left
+ * @param squaredInputs If set, increases the sensitivity at low speeds
+ */
+void RobotDrive::ArcadeDrive(double moveValue, double rotateValue,
+                             bool squaredInputs) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+               HALUsageReporting::kRobotDrive_ArcadeStandard);
+    reported = true;
+  }
+
+  // local variables to hold the computed PWM values for the motors
+  double leftMotorOutput;
+  double rightMotorOutput;
+
+  moveValue = Limit(moveValue);
+  rotateValue = Limit(rotateValue);
+
+  if (squaredInputs) {
+    // square the inputs (while preserving the sign) to increase fine control
+    // while permitting full power
+    if (moveValue >= 0.0) {
+      moveValue = (moveValue * moveValue);
+    } else {
+      moveValue = -(moveValue * moveValue);
+    }
+    if (rotateValue >= 0.0) {
+      rotateValue = (rotateValue * rotateValue);
+    } else {
+      rotateValue = -(rotateValue * rotateValue);
+    }
+  }
+
+  if (moveValue > 0.0) {
+    if (rotateValue > 0.0) {
+      leftMotorOutput = moveValue - rotateValue;
+      rightMotorOutput = std::max(moveValue, rotateValue);
+    } else {
+      leftMotorOutput = std::max(moveValue, -rotateValue);
+      rightMotorOutput = moveValue + rotateValue;
+    }
+  } else {
+    if (rotateValue > 0.0) {
+      leftMotorOutput = -std::max(-moveValue, rotateValue);
+      rightMotorOutput = moveValue + rotateValue;
+    } else {
+      leftMotorOutput = moveValue - rotateValue;
+      rightMotorOutput = -std::max(-moveValue, -rotateValue);
+    }
+  }
+  SetLeftRightMotorOutputs(leftMotorOutput, rightMotorOutput);
+}
+
+/**
+ * Drive method for Mecanum wheeled robots.
+ *
+ * A method for driving with Mecanum wheeled robots. There are 4 wheels
+ * on the robot, arranged so that the front and back wheels are toed in 45
+ * degrees.
+ * When looking at the wheels from the top, the roller axles should form an X
+ * across the robot.
+ *
+ * This is designed to be directly driven by joystick axes.
+ *
+ * @param x         The speed that the robot should drive in the X direction.
+ *                  [-1.0..1.0]
+ * @param y         The speed that the robot should drive in the Y direction.
+ *                  This input is inverted to match the forward == -1.0 that
+ *                  joysticks produce. [-1.0..1.0]
+ * @param rotation  The rate of rotation for the robot that is completely
+ *                  independent of the translation. [-1.0..1.0]
+ * @param gyroAngle The current angle reading from the gyro.  Use this to
+ *                  implement field-oriented controls.
+ */
+void RobotDrive::MecanumDrive_Cartesian(double x, double y, double rotation,
+                                        double gyroAngle) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+               HALUsageReporting::kRobotDrive_MecanumCartesian);
+    reported = true;
+  }
+
+  double xIn = x;
+  double yIn = y;
+  // Negate y for the joystick.
+  yIn = -yIn;
+  // Compenstate for gyro angle.
+  RotateVector(xIn, yIn, gyroAngle);
+
+  double wheelSpeeds[kMaxNumberOfMotors];
+  wheelSpeeds[kFrontLeftMotor] = xIn + yIn + rotation;
+  wheelSpeeds[kFrontRightMotor] = -xIn + yIn - rotation;
+  wheelSpeeds[kRearLeftMotor] = -xIn + yIn + rotation;
+  wheelSpeeds[kRearRightMotor] = xIn + yIn - rotation;
+
+  Normalize(wheelSpeeds);
+
+  m_frontLeftMotor->Set(wheelSpeeds[kFrontLeftMotor] * m_maxOutput);
+  m_frontRightMotor->Set(wheelSpeeds[kFrontRightMotor] * m_maxOutput);
+  m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_maxOutput);
+  m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_maxOutput);
+
+  m_safetyHelper->Feed();
+}
+
+/**
+ * Drive method for Mecanum wheeled robots.
+ *
+ * A method for driving with Mecanum wheeled robots. There are 4 wheels
+ * on the robot, arranged so that the front and back wheels are toed in 45
+ * degrees.
+ * When looking at the wheels from the top, the roller axles should form an X
+ * across the robot.
+ *
+ * @param magnitude The speed that the robot should drive in a given direction.
+ *                  [-1.0..1.0]
+ * @param direction The direction the robot should drive in degrees. The
+ *                  direction and maginitute are independent of the rotation
+ *                  rate.
+ * @param rotation  The rate of rotation for the robot that is completely
+ *                  independent of the magnitute or direction. [-1.0..1.0]
+ */
+void RobotDrive::MecanumDrive_Polar(double magnitude, double direction,
+                                    double rotation) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+               HALUsageReporting::kRobotDrive_MecanumPolar);
+    reported = true;
+  }
+
+  // Normalized for full power along the Cartesian axes.
+  magnitude = Limit(magnitude) * std::sqrt(2.0);
+  // The rollers are at 45 degree angles.
+  double dirInRad = (direction + 45.0) * 3.14159 / 180.0;
+  double cosD = std::cos(dirInRad);
+  double sinD = std::sin(dirInRad);
+
+  double wheelSpeeds[kMaxNumberOfMotors];
+  wheelSpeeds[kFrontLeftMotor] = sinD * magnitude + rotation;
+  wheelSpeeds[kFrontRightMotor] = cosD * magnitude - rotation;
+  wheelSpeeds[kRearLeftMotor] = cosD * magnitude + rotation;
+  wheelSpeeds[kRearRightMotor] = sinD * magnitude - rotation;
+
+  Normalize(wheelSpeeds);
+
+  m_frontLeftMotor->Set(wheelSpeeds[kFrontLeftMotor] * m_maxOutput);
+  m_frontRightMotor->Set(wheelSpeeds[kFrontRightMotor] * m_maxOutput);
+  m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_maxOutput);
+  m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_maxOutput);
+
+  m_safetyHelper->Feed();
+}
+
+/**
+ * Holonomic Drive method for Mecanum wheeled robots.
+ *
+ * This is an alias to MecanumDrive_Polar() for backward compatability
+ *
+ * @param magnitude The speed that the robot should drive in a given direction.
+ *                  [-1.0..1.0]
+ * @param direction The direction the robot should drive. The direction and
+ *                  magnitude are independent of the rotation rate.
+ * @param rotation  The rate of rotation for the robot that is completely
+ *                  independent of the magnitude or direction.  [-1.0..1.0]
+ */
+void RobotDrive::HolonomicDrive(double magnitude, double direction,
+                                double rotation) {
+  MecanumDrive_Polar(magnitude, direction, rotation);
+}
+
+/**
+ * Set the speed of the right and left motors.
+ *
+ * This is used once an appropriate drive setup function is called such as
+ * TwoWheelDrive(). The motors are set to "leftOutput" and "rightOutput"
+ * and includes flipping the direction of one side for opposing motors.
+ *
+ * @param leftOutput  The speed to send to the left side of the robot.
+ * @param rightOutput The speed to send to the right side of the robot.
+ */
+void RobotDrive::SetLeftRightMotorOutputs(double leftOutput,
+                                          double rightOutput) {
+  wpi_assert(m_rearLeftMotor != nullptr && m_rearRightMotor != nullptr);
+
+  if (m_frontLeftMotor != nullptr)
+    m_frontLeftMotor->Set(Limit(leftOutput) * m_maxOutput);
+  m_rearLeftMotor->Set(Limit(leftOutput) * m_maxOutput);
+
+  if (m_frontRightMotor != nullptr)
+    m_frontRightMotor->Set(-Limit(rightOutput) * m_maxOutput);
+  m_rearRightMotor->Set(-Limit(rightOutput) * m_maxOutput);
+
+  m_safetyHelper->Feed();
+}
+
+/**
+ * Limit motor values to the -1.0 to +1.0 range.
+ */
+double RobotDrive::Limit(double num) {
+  if (num > 1.0) {
+    return 1.0;
+  }
+  if (num < -1.0) {
+    return -1.0;
+  }
+  return num;
+}
+
+/**
+ * Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.
+ */
+void RobotDrive::Normalize(double* wheelSpeeds) {
+  double maxMagnitude = std::fabs(wheelSpeeds[0]);
+  int i;
+  for (i = 1; i < kMaxNumberOfMotors; i++) {
+    double temp = std::fabs(wheelSpeeds[i]);
+    if (maxMagnitude < temp) maxMagnitude = temp;
+  }
+  if (maxMagnitude > 1.0) {
+    for (i = 0; i < kMaxNumberOfMotors; i++) {
+      wheelSpeeds[i] = wheelSpeeds[i] / maxMagnitude;
+    }
+  }
+}
+
+/**
+ * Rotate a vector in Cartesian space.
+ */
+void RobotDrive::RotateVector(double& x, double& y, double angle) {
+  double cosA = std::cos(angle * (3.14159 / 180.0));
+  double sinA = std::sin(angle * (3.14159 / 180.0));
+  double xOut = x * cosA - y * sinA;
+  double yOut = x * sinA + y * cosA;
+  x = xOut;
+  y = yOut;
+}
+
+/*
+ * Invert a motor direction.
+ *
+ * This is used when a motor should run in the opposite direction as the drive
+ * code would normally run it. Motors that are direct drive would be inverted,
+ * the Drive code assumes that the motors are geared with one reversal.
+ *
+ * @param motor      The motor index to invert.
+ * @param isInverted True if the motor should be inverted when operated.
+ */
+void RobotDrive::SetInvertedMotor(MotorType motor, bool isInverted) {
+  if (motor < 0 || motor > 3) {
+    wpi_setWPIError(InvalidMotorIndex);
+    return;
+  }
+  switch (motor) {
+    case kFrontLeftMotor:
+      m_frontLeftMotor->SetInverted(isInverted);
+      break;
+    case kFrontRightMotor:
+      m_frontRightMotor->SetInverted(isInverted);
+      break;
+    case kRearLeftMotor:
+      m_rearLeftMotor->SetInverted(isInverted);
+      break;
+    case kRearRightMotor:
+      m_rearRightMotor->SetInverted(isInverted);
+      break;
+  }
+}
+
+/**
+ * Set the turning sensitivity.
+ *
+ * This only impacts the Drive() entry-point.
+ *
+ * @param sensitivity Effectively sets the turning sensitivity (or turn radius
+ *                    for a given value)
+ */
+void RobotDrive::SetSensitivity(double sensitivity) {
+  m_sensitivity = sensitivity;
+}
+
+/**
+ * Configure the scaling factor for using RobotDrive with motor controllers in a
+ * mode other than PercentVbus.
+ *
+ * @param maxOutput Multiplied with the output percentage computed by the drive
+ *                  functions.
+ */
+void RobotDrive::SetMaxOutput(double maxOutput) { m_maxOutput = maxOutput; }
+
+void RobotDrive::SetExpiration(double timeout) {
+  m_safetyHelper->SetExpiration(timeout);
+}
+
+double RobotDrive::GetExpiration() const {
+  return m_safetyHelper->GetExpiration();
+}
+
+bool RobotDrive::IsAlive() const { return m_safetyHelper->IsAlive(); }
+
+bool RobotDrive::IsSafetyEnabled() const {
+  return m_safetyHelper->IsSafetyEnabled();
+}
+
+void RobotDrive::SetSafetyEnabled(bool enabled) {
+  m_safetyHelper->SetSafetyEnabled(enabled);
+}
+
+void RobotDrive::GetDescription(std::ostringstream& desc) const {
+  desc << "RobotDrive";
+}
+
+void RobotDrive::StopMotor() {
+  if (m_frontLeftMotor != nullptr) m_frontLeftMotor->StopMotor();
+  if (m_frontRightMotor != nullptr) m_frontRightMotor->StopMotor();
+  if (m_rearLeftMotor != nullptr) m_rearLeftMotor->StopMotor();
+  if (m_rearRightMotor != nullptr) m_rearRightMotor->StopMotor();
+  m_safetyHelper->Feed();
+}
diff --git a/wpilibc/athena/src/SD540.cpp b/wpilibc/athena/src/SD540.cpp
new file mode 100644
index 0000000..02430ff
--- /dev/null
+++ b/wpilibc/athena/src/SD540.cpp
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SD540.h"
+
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.h"
+
+using namespace frc;
+
+/**
+ * Note that the SD540 uses the following bounds for PWM values. These values
+ * should work reasonably well for most controllers, but if users experience
+ * issues such as asymmetric behavior around the deadband or inability to
+ * saturate the controller in either direction, calibration is recommended.
+ * The calibration procedure can be found in the SD540 User Manual available
+ * from Mindsensors.
+ *
+ *   2.05ms = full "forward"
+ *   1.55ms = the "high end" of the deadband range
+ *   1.50ms = center of the deadband range (off)
+ *   1.44ms = the "low end" of the deadband range
+ *   0.94ms = full "reverse"
+ */
+
+/**
+ * Constructor for a SD540.
+ *
+ * @param channel The PWM channel that the SD540 is attached to. 0-9 are
+ *                on-board, 10-19 are on the MXP port
+ */
+SD540::SD540(int channel) : PWMSpeedController(channel) {
+  SetBounds(2.05, 1.55, 1.50, 1.44, .94);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_MindsensorsSD540, GetChannel());
+  LiveWindow::GetInstance()->AddActuator("SD540", GetChannel(), this);
+}
diff --git a/wpilibc/athena/src/SPI.cpp b/wpilibc/athena/src/SPI.cpp
new file mode 100644
index 0000000..5fe18ca
--- /dev/null
+++ b/wpilibc/athena/src/SPI.cpp
@@ -0,0 +1,300 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SPI.h"
+
+#include <cstring>
+
+#include "HAL/HAL.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Constructor
+ *
+ * @param SPIport the physical SPI port
+ */
+SPI::SPI(Port SPIport) {
+  m_port = SPIport;
+  int32_t status = 0;
+  HAL_InitializeSPI(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  static int instances = 0;
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_SPI, instances);
+}
+
+/**
+ * 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);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Configure the chip select line to be active low.
+ */
+void SPI::SetChipSelectActiveLow() {
+  int32_t status = 0;
+  HAL_SetSPIChipSelectActiveLow(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(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) {
+    auto dataToSend = new uint8_t[size];
+    std::memset(dataToSend, 0, size);
+    retVal = HAL_TransactionSPI(m_port, dataToSend, 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;
+}
+
+/**
+ * Initialize the accumulator.
+ *
+ * @param period     Time between reads
+ * @param cmd        SPI command to send to request data
+ * @param xfer_size  SPI transfer size, in bytes
+ * @param valid_mask Mask to apply to received data for validity checking
+ * @param valid_data After valid_mask is applied, required matching value for
+ *                   validity checking
+ * @param data_shift Bit shift to apply to received data to get actual data
+ *                   value
+ * @param data_size  Size (in bits) of data field
+ * @param is_signed  Is data field signed?
+ * @param big_endian Is device big endian?
+ */
+void SPI::InitAccumulator(double period, int cmd, int xfer_size, int valid_mask,
+                          int valid_value, int data_shift, int data_size,
+                          bool is_signed, bool big_endian) {
+  int32_t status = 0;
+  HAL_InitSPIAccumulator(m_port, static_cast<int32_t>(period * 1e6), cmd,
+                         xfer_size, valid_mask, valid_value, data_shift,
+                         data_size, is_signed, big_endian, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Frees the accumulator.
+ */
+void SPI::FreeAccumulator() {
+  int32_t status = 0;
+  HAL_FreeSPIAccumulator(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Resets the accumulator to zero.
+ */
+void SPI::ResetAccumulator() {
+  int32_t status = 0;
+  HAL_ResetSPIAccumulator(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Set the center value of the accumulator.
+ *
+ * The center value is subtracted from each value before it is added to the
+ * accumulator. This is used for the center value of devices like gyros and
+ * accelerometers to make integration work and to take the device offset into
+ * account when integrating.
+ */
+void SPI::SetAccumulatorCenter(int center) {
+  int32_t status = 0;
+  HAL_SetSPIAccumulatorCenter(m_port, center, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Set the accumulator's deadband.
+ */
+void SPI::SetAccumulatorDeadband(int deadband) {
+  int32_t status = 0;
+  HAL_SetSPIAccumulatorDeadband(m_port, deadband, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Read the last value read by the accumulator engine.
+ */
+int SPI::GetAccumulatorLastValue() const {
+  int32_t status = 0;
+  int retVal = HAL_GetSPIAccumulatorLastValue(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Read the accumulated value.
+ *
+ * @return The 64-bit value accumulated since the last Reset().
+ */
+int64_t SPI::GetAccumulatorValue() const {
+  int32_t status = 0;
+  int64_t retVal = HAL_GetSPIAccumulatorValue(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Read the number of accumulated values.
+ *
+ * Read the count of the accumulated values since the accumulator was last
+ * Reset().
+ *
+ * @return The number of times samples from the channel were accumulated.
+ */
+int64_t SPI::GetAccumulatorCount() const {
+  int32_t status = 0;
+  int64_t retVal = HAL_GetSPIAccumulatorCount(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Read the average of the accumulated value.
+ *
+ * @return The accumulated average value (value / count).
+ */
+double SPI::GetAccumulatorAverage() const {
+  int32_t status = 0;
+  double retVal = HAL_GetSPIAccumulatorAverage(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Read the accumulated value and the number of accumulated values atomically.
+ *
+ * This function reads the value and count atomically.
+ * This can be used for averaging.
+ *
+ * @param value Pointer to the 64-bit accumulated output.
+ * @param count Pointer to the number of accumulation cycles.
+ */
+void SPI::GetAccumulatorOutput(int64_t& value, int64_t& count) const {
+  int32_t status = 0;
+  HAL_GetSPIAccumulatorOutput(m_port, &value, &count, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
diff --git a/wpilibc/athena/src/SafePWM.cpp b/wpilibc/athena/src/SafePWM.cpp
new file mode 100644
index 0000000..cd62192
--- /dev/null
+++ b/wpilibc/athena/src/SafePWM.cpp
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "SafePWM.h"
+
+using namespace frc;
+
+/**
+ * Constructor for a SafePWM object taking a channel number.
+ *
+ * @param channel The PWM channel number 0-9 are on-board, 10-19 are on the MXP
+ *                port
+ */
+SafePWM::SafePWM(int channel) : PWM(channel) {
+  m_safetyHelper = std::make_unique<MotorSafetyHelper>(this);
+  m_safetyHelper->SetSafetyEnabled(false);
+}
+
+/**
+ * Set the expiration time for the PWM object.
+ *
+ * @param timeout The timeout (in seconds) for this motor object
+ */
+void SafePWM::SetExpiration(double timeout) {
+  m_safetyHelper->SetExpiration(timeout);
+}
+
+/**
+ * Return the expiration time for the PWM object.
+ *
+ * @returns The expiration time value.
+ */
+double SafePWM::GetExpiration() const {
+  return m_safetyHelper->GetExpiration();
+}
+
+/**
+ * Check if the PWM object is currently alive or stopped due to a timeout.
+ *
+ * @return a bool value that is true if the motor has NOT timed out and should
+ *         still be running.
+ */
+bool SafePWM::IsAlive() const { return m_safetyHelper->IsAlive(); }
+
+/**
+ * Stop the motor associated with this PWM object.
+ *
+ * This is called by the MotorSafetyHelper object when it has a timeout for this
+ * PWM and needs to stop it from running.
+ */
+void SafePWM::StopMotor() { SetDisabled(); }
+
+/**
+ * Enable/disable motor safety for this device.
+ *
+ * Turn on and off the motor safety option for this PWM object.
+ *
+ * @param enabled True if motor safety is enforced for this object
+ */
+void SafePWM::SetSafetyEnabled(bool enabled) {
+  m_safetyHelper->SetSafetyEnabled(enabled);
+}
+
+/**
+ * Check if motor safety is enabled for this object.
+ *
+ * @returns True if motor safety is enforced for this object
+ */
+bool SafePWM::IsSafetyEnabled() const {
+  return m_safetyHelper->IsSafetyEnabled();
+}
+
+void SafePWM::GetDescription(std::ostringstream& desc) const {
+  desc << "PWM " << GetChannel();
+}
+
+/**
+ * Feed the MotorSafety timer when setting the speed.
+ *
+ * This method is called by the subclass motor whenever it updates its speed,
+ * thereby reseting the timeout value.
+ *
+ * @param speed Value to pass to the PWM class
+ */
+void SafePWM::SetSpeed(double speed) {
+  PWM::SetSpeed(speed);
+  m_safetyHelper->Feed();
+}
diff --git a/wpilibc/athena/src/SampleRobot.cpp b/wpilibc/athena/src/SampleRobot.cpp
new file mode 100644
index 0000000..014730e
--- /dev/null
+++ b/wpilibc/athena/src/SampleRobot.cpp
@@ -0,0 +1,149 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SampleRobot.h"
+
+#include "DriverStation.h"
+#include "LiveWindow/LiveWindow.h"
+#include "Timer.h"
+#include "networktables/NetworkTable.h"
+
+using namespace frc;
+
+SampleRobot::SampleRobot() : m_robotMainOverridden(true) {}
+
+/**
+ * Robot-wide initialization code should go here.
+ *
+ * Users should override this method for default Robot-wide initialization which
+ * will be called when the robot is first powered on. It will be called exactly
+ * one time.
+ *
+ * Warning: the Driver Station "Robot Code" light and FMS "Robot Ready"
+ * indicators will be off until RobotInit() exits. Code in RobotInit() that
+ * waits for enable will cause the robot to never indicate that the code is
+ * ready, causing the robot to be bypassed in a match.
+ */
+void SampleRobot::RobotInit() {
+  std::printf("Default %s() method... Override me!\n", __FUNCTION__);
+}
+
+/**
+ * Disabled should go here.
+ *
+ * Programmers should override this method to run code that should run while the
+ * field is disabled.
+ */
+void SampleRobot::Disabled() {
+  std::printf("Default %s() method... Override me!\n", __FUNCTION__);
+}
+
+/**
+ * Autonomous should go here.
+ *
+ * Programmers should override this method to run code that should run while the
+ * field is in the autonomous period. This will be called once each time the
+ * robot enters the autonomous state.
+ */
+void SampleRobot::Autonomous() {
+  std::printf("Default %s() method... Override me!\n", __FUNCTION__);
+}
+
+/**
+ * Operator control (tele-operated) code should go here.
+ *
+ * Programmers should override this method to run code that should run while the
+ * field is in the Operator Control (tele-operated) period. This is called once
+ * each time the robot enters the teleop state.
+ */
+void SampleRobot::OperatorControl() {
+  std::printf("Default %s() method... Override me!\n", __FUNCTION__);
+}
+
+/**
+ * Test program should go here.
+ *
+ * Programmers should override this method to run code that executes while the
+ * robot is in test mode. This will be called once whenever the robot enters
+ * test mode
+ */
+void SampleRobot::Test() {
+  std::printf("Default %s() method... Override me!\n", __FUNCTION__);
+}
+
+/**
+ * Robot main program for free-form programs.
+ *
+ * This should be overridden by user subclasses if the intent is to not use the
+ * Autonomous() and OperatorControl() methods. In that case, the program is
+ * responsible for sensing when to run the autonomous and operator control
+ * functions in their program.
+ *
+ * This method will be called immediately after the constructor is called. If it
+ * has not been overridden by a user subclass (i.e. the default version runs),
+ * then the Autonomous() and OperatorControl() methods will be called.
+ */
+void SampleRobot::RobotMain() { m_robotMainOverridden = false; }
+
+/**
+ * Start a competition.
+ *
+ * This code needs to track the order of the field starting to ensure that
+ * everything happens in the right order. Repeatedly run the correct method,
+ * either Autonomous or OperatorControl or Test when the robot is enabled.
+ * After running the correct method, wait for some state to change, either the
+ * other mode starts or the robot is disabled. Then go back and wait for the
+ * robot to be enabled again.
+ */
+void SampleRobot::StartCompetition() {
+  LiveWindow* lw = LiveWindow::GetInstance();
+
+  HAL_Report(HALUsageReporting::kResourceType_Framework,
+             HALUsageReporting::kFramework_Simple);
+
+  NetworkTable::GetTable("LiveWindow")
+      ->GetSubTable("~STATUS~")
+      ->PutBoolean("LW Enabled", false);
+
+  RobotInit();
+
+  // Tell the DS that the robot is ready to be enabled
+  HAL_ObserveUserProgramStarting();
+
+  RobotMain();
+
+  if (!m_robotMainOverridden) {
+    // first and one-time initialization
+    lw->SetEnabled(false);
+
+    while (true) {
+      if (IsDisabled()) {
+        m_ds.InDisabled(true);
+        Disabled();
+        m_ds.InDisabled(false);
+        while (IsDisabled()) m_ds.WaitForData();
+      } else if (IsAutonomous()) {
+        m_ds.InAutonomous(true);
+        Autonomous();
+        m_ds.InAutonomous(false);
+        while (IsAutonomous() && IsEnabled()) m_ds.WaitForData();
+      } else if (IsTest()) {
+        lw->SetEnabled(true);
+        m_ds.InTest(true);
+        Test();
+        m_ds.InTest(false);
+        while (IsTest() && IsEnabled()) m_ds.WaitForData();
+        lw->SetEnabled(false);
+      } else {
+        m_ds.InOperatorControl(true);
+        OperatorControl();
+        m_ds.InOperatorControl(false);
+        while (IsOperatorControl() && IsEnabled()) m_ds.WaitForData();
+      }
+    }
+  }
+}
diff --git a/wpilibc/athena/src/SensorBase.cpp b/wpilibc/athena/src/SensorBase.cpp
new file mode 100644
index 0000000..1a4987c
--- /dev/null
+++ b/wpilibc/athena/src/SensorBase.cpp
@@ -0,0 +1,117 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "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 "WPIErrors.h"
+
+using namespace frc;
+
+const int SensorBase::kDigitalChannels = HAL_GetNumDigitalChannels();
+const int SensorBase::kAnalogInputs = HAL_GetNumAnalogInputs();
+const int SensorBase::kSolenoidChannels = HAL_GetNumSolenoidChannels();
+const int SensorBase::kSolenoidModules = HAL_GetNumPCMModules();
+const int SensorBase::kPwmChannels = HAL_GetNumPWMChannels();
+const int SensorBase::kRelayChannels = HAL_GetNumRelayHeaders();
+const int SensorBase::kPDPChannels = HAL_GetNumPDPChannels();
+
+/**
+ * Check that the solenoid module number is valid.
+ *
+ * @return Solenoid module is valid and present
+ */
+bool SensorBase::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 SensorBase::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 SensorBase::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 SensorBase::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 SensorBase::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 SensorBase::CheckAnalogOutputChannel(int channel) {
+  return HAL_CheckAnalogOutputChannel(channel);
+}
+
+/**
+ * Verify that the solenoid channel number is within limits.
+ *
+ * @return Solenoid channel is valid
+ */
+bool SensorBase::CheckSolenoidChannel(int channel) {
+  return HAL_CheckSolenoidChannel(channel);
+}
+
+/**
+ * Verify that the power distribution channel number is within limits.
+ *
+ * @return PDP channel is valid
+ */
+bool SensorBase::CheckPDPChannel(int channel) {
+  return HAL_CheckPDPModule(channel);
+}
diff --git a/wpilibc/athena/src/SerialPort.cpp b/wpilibc/athena/src/SerialPort.cpp
new file mode 100644
index 0000000..56435a9
--- /dev/null
+++ b/wpilibc/athena/src/SerialPort.cpp
@@ -0,0 +1,264 @@
+/*----------------------------------------------------------------------------*/
+/* 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/SerialPort.h"
+#include "SerialPort.h"
+
+#include "HAL/HAL.h"
+
+// static ViStatus _VI_FUNCH ioCompleteHandler (ViSession vi, ViEventType
+// eventType, ViEvent event, ViAddr userHandle);
+
+using namespace frc;
+
+/**
+ * Create an instance of a Serial Port class.
+ *
+ * @param baudRate The baud rate to configure the serial port.
+ * @param port     The physical port to use
+ * @param dataBits The number of data bits per transfer.  Valid values are
+ *                 between 5 and 8 bits.
+ * @param parity   Select the type of parity checking to use.
+ * @param stopBits The number of stop bits to use as defined by the enum
+ *                 StopBits.
+ */
+SerialPort::SerialPort(int baudRate, Port port, int dataBits,
+                       SerialPort::Parity parity,
+                       SerialPort::StopBits stopBits) {
+  int32_t status = 0;
+
+  m_port = port;
+
+  HAL_InitializeSerialPort(static_cast<HAL_SerialPort>(port), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  // Don't continue if initialization failed
+  if (status < 0) return;
+  HAL_SetSerialBaudRate(static_cast<HAL_SerialPort>(port), baudRate, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  HAL_SetSerialDataBits(static_cast<HAL_SerialPort>(port), dataBits, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  HAL_SetSerialParity(static_cast<HAL_SerialPort>(port), parity, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  HAL_SetSerialStopBits(static_cast<HAL_SerialPort>(port), stopBits, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  // Set the default timeout to 5 seconds.
+  SetTimeout(5.0);
+
+  // Don't wait until the buffer is full to transmit.
+  SetWriteBufferMode(kFlushOnAccess);
+
+  EnableTermination();
+
+  // viInstallHandler(m_portHandle, VI_EVENT_IO_COMPLETION, ioCompleteHandler,
+  // this);
+  // viEnableEvent(m_portHandle, VI_EVENT_IO_COMPLETION, VI_HNDLR, VI_NULL);
+
+  HAL_Report(HALUsageReporting::kResourceType_SerialPort, 0);
+}
+
+/**
+ * Destructor.
+ */
+SerialPort::~SerialPort() {
+  int32_t status = 0;
+  HAL_CloseSerial(static_cast<HAL_SerialPort>(m_port), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Set the type of flow control to enable on this port.
+ *
+ * By default, flow control is disabled.
+ */
+void SerialPort::SetFlowControl(SerialPort::FlowControl flowControl) {
+  int32_t status = 0;
+  HAL_SetSerialFlowControl(static_cast<HAL_SerialPort>(m_port), flowControl,
+                           &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Enable termination and specify the termination character.
+ *
+ * Termination is currently only implemented for receive.
+ * When the the terminator is recieved, the Read() or Scanf() will return
+ * fewer bytes than requested, stopping after the terminator.
+ *
+ * @param terminator The character to use for termination.
+ */
+void SerialPort::EnableTermination(char terminator) {
+  int32_t status = 0;
+  HAL_EnableSerialTermination(static_cast<HAL_SerialPort>(m_port), terminator,
+                              &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Disable termination behavior.
+ */
+void SerialPort::DisableTermination() {
+  int32_t status = 0;
+  HAL_DisableSerialTermination(static_cast<HAL_SerialPort>(m_port), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Get the number of bytes currently available to read from the serial port.
+ *
+ * @return The number of bytes available to read
+ */
+int SerialPort::GetBytesReceived() {
+  int32_t status = 0;
+  int retVal =
+      HAL_GetSerialBytesReceived(static_cast<HAL_SerialPort>(m_port), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Read raw bytes out of the buffer.
+ *
+ * @param buffer Pointer to the buffer to store the bytes in.
+ * @param count  The maximum number of bytes to read.
+ * @return The number of bytes actually read into the buffer.
+ */
+int SerialPort::Read(char* buffer, int count) {
+  int32_t status = 0;
+  int retVal = HAL_ReadSerial(static_cast<HAL_SerialPort>(m_port), buffer,
+                              count, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Write raw bytes to the buffer. Deprecated, please use StringRef overload. Use
+ * Write({data, len}) to get a buffer that is shorter then the length of the
+ * std::string.
+ *
+ * @param buffer Pointer to the buffer to read the bytes from. If string.size()
+ * is less then count, only the length of string.size() will be sent.
+ * @param count  The maximum number of bytes to write.
+ * @return The number of bytes actually written into the port.
+ */
+int SerialPort::Write(const std::string& buffer, int count) {
+  return Write(llvm::StringRef(
+      buffer.data(), std::min(static_cast<int>(buffer.size()), count)));
+}
+
+/**
+ * Write raw bytes to the buffer.
+ *
+ * @param buffer Pointer to the buffer to read the bytes from.
+ * @param count  The maximum number of bytes to write.
+ * @return The number of bytes actually written into the port.
+ */
+int SerialPort::Write(const char* buffer, int count) {
+  return Write(llvm::StringRef(buffer, static_cast<size_t>(count)));
+}
+
+/**
+ * Write raw bytes to the buffer.
+ *
+ * @param buffer StringRef to the buffer to read the bytes from.
+ * @return The number of bytes actually written into the port.
+ */
+int SerialPort::Write(llvm::StringRef buffer) {
+  int32_t status = 0;
+  int retVal = HAL_WriteSerial(static_cast<HAL_SerialPort>(m_port),
+                               buffer.data(), buffer.size(), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Configure the timeout of the serial port.
+ *
+ * This defines the timeout for transactions with the hardware.
+ * It will affect reads and very large writes.
+ *
+ * @param timeout The number of seconds to to wait for I/O.
+ */
+void SerialPort::SetTimeout(double timeout) {
+  int32_t status = 0;
+  HAL_SetSerialTimeout(static_cast<HAL_SerialPort>(m_port), timeout, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Specify the size of the input buffer.
+ *
+ * Specify the amount of data that can be stored before data
+ * from the device is returned to Read or Scanf.  If you want
+ * data that is recieved to be returned immediately, set this to 1.
+ *
+ * It the buffer is not filled before the read timeout expires, all
+ * data that has been received so far will be returned.
+ *
+ * @param size The read buffer size.
+ */
+void SerialPort::SetReadBufferSize(int size) {
+  int32_t status = 0;
+  HAL_SetSerialReadBufferSize(static_cast<HAL_SerialPort>(m_port), size,
+                              &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Specify the size of the output buffer.
+ *
+ * Specify the amount of data that can be stored before being
+ * transmitted to the device.
+ *
+ * @param size The write buffer size.
+ */
+void SerialPort::SetWriteBufferSize(int size) {
+  int32_t status = 0;
+  HAL_SetSerialWriteBufferSize(static_cast<HAL_SerialPort>(m_port), size,
+                               &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Specify the flushing behavior of the output buffer.
+ *
+ * When set to kFlushOnAccess, data is synchronously written to the serial port
+ * after each call to either Printf() or Write().
+ *
+ * When set to kFlushWhenFull, data will only be written to the serial port when
+ * the buffer is full or when Flush() is called.
+ *
+ * @param mode The write buffer mode.
+ */
+void SerialPort::SetWriteBufferMode(SerialPort::WriteBufferMode mode) {
+  int32_t status = 0;
+  HAL_SetSerialWriteMode(static_cast<HAL_SerialPort>(m_port), mode, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Force the output buffer to be written to the port.
+ *
+ * This is used when SetWriteBufferMode() is set to kFlushWhenFull to force a
+ * flush before the buffer is full.
+ */
+void SerialPort::Flush() {
+  int32_t status = 0;
+  HAL_FlushSerial(static_cast<HAL_SerialPort>(m_port), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Reset the serial port driver to a known state.
+ *
+ * Empty the transmit and receive buffers in the device and formatted I/O.
+ */
+void SerialPort::Reset() {
+  int32_t status = 0;
+  HAL_ClearSerial(static_cast<HAL_SerialPort>(m_port), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
diff --git a/wpilibc/athena/src/Servo.cpp b/wpilibc/athena/src/Servo.cpp
new file mode 100644
index 0000000..0a425ba
--- /dev/null
+++ b/wpilibc/athena/src/Servo.cpp
@@ -0,0 +1,134 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Servo.h"
+
+#include "LiveWindow/LiveWindow.h"
+
+using namespace frc;
+
+constexpr double Servo::kMaxServoAngle;
+constexpr double Servo::kMinServoAngle;
+
+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) : SafePWM(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);
+
+  //  std::printf("Done initializing servo %d\n", channel);
+}
+
+Servo::~Servo() {
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+/**
+ * Set the servo position.
+ *
+ * Servo values range from 0.0 to 1.0 corresponding to the range of full left to
+ * full right.
+ *
+ * @param value Position from 0.0 to 1.0.
+ */
+void Servo::Set(double value) { SetPosition(value); }
+
+/**
+ * Set the servo to offline.
+ *
+ * Set the servo raw value to 0 (undriven)
+ */
+void Servo::SetOffline() { SetRaw(0); }
+
+/**
+ * Get the servo position.
+ *
+ * Servo values range from 0.0 to 1.0 corresponding to the range of full left to
+ * full right.
+ *
+ * @return Position from 0.0 to 1.0.
+ */
+double Servo::Get() const { return GetPosition(); }
+
+/**
+ * Set the servo angle.
+ *
+ * Assume that the servo angle is linear with respect to the PWM value (big
+ * assumption, need to test).
+ *
+ * Servo angles that are out of the supported range of the servo simply
+ * "saturate" in that direction. In other words, if the servo has a range of
+ * (X degrees to Y degrees) than angles of less than X result in an angle of
+ * X being set and angles of more than Y degrees result in an angle of Y being
+ * set.
+ *
+ * @param degrees The angle in degrees to set the servo.
+ */
+void Servo::SetAngle(double degrees) {
+  if (degrees < kMinServoAngle) {
+    degrees = kMinServoAngle;
+  } else if (degrees > kMaxServoAngle) {
+    degrees = kMaxServoAngle;
+  }
+
+  SetPosition((degrees - kMinServoAngle) / GetServoAngleRange());
+}
+
+/**
+ * Get the servo angle.
+ *
+ * Assume that the servo angle is linear with respect to the PWM value (big
+ * assumption, need to test).
+ *
+ * @return The angle in degrees to which the servo is set.
+ */
+double Servo::GetAngle() const {
+  return GetPosition() * GetServoAngleRange() + kMinServoAngle;
+}
+
+void Servo::ValueChanged(ITable* source, llvm::StringRef key,
+                         std::shared_ptr<nt::Value> value, bool isNew) {
+  if (!value->IsDouble()) return;
+  Set(value->GetDouble());
+}
+
+void Servo::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", Get());
+  }
+}
+
+void Servo::StartLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->AddTableListener("Value", this, true);
+  }
+}
+
+void Servo::StopLiveWindowMode() {
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+std::string Servo::GetSmartDashboardType() const { return "Servo"; }
+
+void Servo::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> Servo::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/Solenoid.cpp b/wpilibc/athena/src/Solenoid.cpp
new file mode 100644
index 0000000..d70c3c3
--- /dev/null
+++ b/wpilibc/athena/src/Solenoid.cpp
@@ -0,0 +1,145 @@
+/*----------------------------------------------------------------------------*/
+/* 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/Solenoid.h"
+#include "Solenoid.h"
+
+#include <sstream>
+
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "LiveWindow/LiveWindow.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Constructor using the default PCM ID (0).
+ *
+ * @param channel The channel on the PCM to control (0..7).
+ */
+Solenoid::Solenoid(int channel)
+    : Solenoid(GetDefaultSolenoidModule(), channel) {}
+
+/**
+ * Constructor.
+ *
+ * @param moduleNumber The CAN ID of the PCM the solenoid is attached to
+ * @param channel      The channel on the PCM to control (0..7).
+ */
+Solenoid::Solenoid(int moduleNumber, int channel)
+    : SolenoidBase(moduleNumber), m_channel(channel) {
+  std::stringstream buf;
+  if (!CheckSolenoidModule(m_moduleNumber)) {
+    buf << "Solenoid Module " << m_moduleNumber;
+    wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf.str());
+    return;
+  }
+  if (!CheckSolenoidChannel(m_channel)) {
+    buf << "Solenoid Module " << m_channel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    return;
+  }
+
+  int32_t status = 0;
+  m_solenoidHandle = HAL_InitializeSolenoidPort(
+      HAL_GetPortWithModule(moduleNumber, channel), &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumSolenoidChannels(),
+                                 channel, HAL_GetErrorMessage(status));
+    m_solenoidHandle = HAL_kInvalidHandle;
+    return;
+  }
+
+  LiveWindow::GetInstance()->AddActuator("Solenoid", m_moduleNumber, m_channel,
+                                         this);
+  HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_channel,
+             m_moduleNumber);
+}
+
+/**
+ * Destructor.
+ */
+Solenoid::~Solenoid() {
+  HAL_FreeSolenoidPort(m_solenoidHandle);
+  if (m_table != nullptr) m_table->RemoveTableListener(this);
+}
+
+/**
+ * Set the value of a solenoid.
+ *
+ * @param on Turn the solenoid output off or on.
+ */
+void Solenoid::Set(bool on) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetSolenoid(m_solenoidHandle, on, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Read the current value of the solenoid.
+ *
+ * @return The current value of the solenoid.
+ */
+bool Solenoid::Get() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = HAL_GetSolenoid(m_solenoidHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Check if solenoid is blacklisted.
+ *
+ * If a solenoid is shorted, it is added to the blacklist and
+ * disabled until power cycle, or until faults are cleared.
+ *
+ * @see ClearAllPCMStickyFaults()
+ *
+ * @return If solenoid is disabled due to short.
+ */
+bool Solenoid::IsBlackListed() const {
+  int value = GetPCMSolenoidBlackList(m_moduleNumber) & (1 << m_channel);
+  return (value != 0);
+}
+
+void Solenoid::ValueChanged(ITable* source, llvm::StringRef key,
+                            std::shared_ptr<nt::Value> value, bool isNew) {
+  if (!value->IsBoolean()) return;
+  Set(value->GetBoolean());
+}
+
+void Solenoid::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutBoolean("Value", Get());
+  }
+}
+
+void Solenoid::StartLiveWindowMode() {
+  Set(false);
+  if (m_table != nullptr) {
+    m_table->AddTableListener("Value", this, true);
+  }
+}
+
+void Solenoid::StopLiveWindowMode() {
+  Set(false);
+  if (m_table != nullptr) {
+    m_table->RemoveTableListener(this);
+  }
+}
+
+std::string Solenoid::GetSmartDashboardType() const { return "Solenoid"; }
+
+void Solenoid::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> Solenoid::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/SolenoidBase.cpp b/wpilibc/athena/src/SolenoidBase.cpp
new file mode 100644
index 0000000..4b53744
--- /dev/null
+++ b/wpilibc/athena/src/SolenoidBase.cpp
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SolenoidBase.h"
+
+#include "HAL/HAL.h"
+#include "HAL/Solenoid.h"
+
+using namespace frc;
+
+/**
+ * Constructor
+ *
+ * @param moduleNumber The CAN PCM ID.
+ */
+SolenoidBase::SolenoidBase(int moduleNumber) : m_moduleNumber(moduleNumber) {}
+
+/**
+ * Read all 8 solenoids as a single byte
+ *
+ * @return The current value of all 8 solenoids on the module.
+ */
+int SolenoidBase::GetAll(int module) const {
+  int value = 0;
+  int32_t status = 0;
+  value = HAL_GetAllSolenoids(static_cast<int>(module), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Reads complete solenoid blacklist for all 8 solenoids as a single byte.
+ *
+ * If a solenoid is shorted, it is added to the blacklist and
+ * disabled until power cycle, or until faults are cleared.
+ * @see ClearAllPCMStickyFaults()
+ *
+ * @return The solenoid blacklist of all 8 solenoids on the module.
+ */
+int SolenoidBase::GetPCMSolenoidBlackList(int module) const {
+  int32_t status = 0;
+  return HAL_GetPCMSolenoidBlackList(static_cast<int>(module), &status);
+}
+
+/**
+ * @return true if PCM sticky fault is set : The common highside solenoid
+ *         voltage rail is too low, most likely a solenoid channel is shorted.
+ */
+bool SolenoidBase::GetPCMSolenoidVoltageStickyFault(int module) const {
+  int32_t status = 0;
+  return HAL_GetPCMSolenoidVoltageStickyFault(static_cast<int>(module),
+                                              &status);
+}
+
+/**
+ * @return true if PCM is in fault state : The common highside solenoid voltage
+ *         rail is too low, most likely a solenoid channel is shorted.
+ */
+bool SolenoidBase::GetPCMSolenoidVoltageFault(int module) const {
+  int32_t status = 0;
+  return HAL_GetPCMSolenoidVoltageFault(static_cast<int>(module), &status);
+}
+
+/**
+ * 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 SolenoidBase::ClearAllPCMStickyFaults(int module) {
+  int32_t status = 0;
+  return HAL_ClearAllPCMStickyFaults(static_cast<int>(module), &status);
+}
diff --git a/wpilibc/athena/src/Spark.cpp b/wpilibc/athena/src/Spark.cpp
new file mode 100644
index 0000000..1790806
--- /dev/null
+++ b/wpilibc/athena/src/Spark.cpp
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Spark.h"
+
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.h"
+
+using namespace frc;
+
+/**
+ * Note that the Spark uses the following bounds for PWM values. These values
+ * should work reasonably well for most controllers, but if users experience
+ * issues such as asymmetric behavior around the deadband or inability to
+ * saturate the controller in either direction, calibration is recommended.
+ * The calibration procedure can be found in the Spark User Manual available
+ * from REV Robotics.
+ *
+ *   2.003ms = full "forward"
+ *   1.55ms = the "high end" of the deadband range
+ *   1.50ms = center of the deadband range (off)
+ *   1.46ms = the "low end" of the deadband range
+ *   0.999ms = full "reverse"
+ */
+
+/**
+ * Constructor for a Spark.
+ *
+ * @param channel The PWM channel that the Spark is attached to. 0-9 are
+ *                on-board, 10-19 are on the MXP port
+ */
+Spark::Spark(int channel) : PWMSpeedController(channel) {
+  SetBounds(2.003, 1.55, 1.50, 1.46, .999);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_RevSPARK, GetChannel());
+  LiveWindow::GetInstance()->AddActuator("Spark", GetChannel(), this);
+}
diff --git a/wpilibc/athena/src/Talon.cpp b/wpilibc/athena/src/Talon.cpp
new file mode 100644
index 0000000..58bc109
--- /dev/null
+++ b/wpilibc/athena/src/Talon.cpp
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Talon.h"
+
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.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) : PWMSpeedController(channel) {
+  /* Note that the Talon uses the following bounds for PWM values. These values
+   * should work reasonably well for most controllers, but if users experience
+   * issues such as asymmetric behavior around the deadband or inability to
+   * saturate the controller in either direction, calibration is recommended.
+   * The calibration procedure can be found in the Talon User Manual available
+   * from CTRE.
+   *
+   *   2.037ms = full "forward"
+   *   1.539ms = the "high end" of the deadband range
+   *   1.513ms = center of the deadband range (off)
+   *   1.487ms = the "low end" of the deadband range
+   *   0.989ms = full "reverse"
+   */
+  SetBounds(2.037, 1.539, 1.513, 1.487, .989);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_Talon, GetChannel());
+  LiveWindow::GetInstance()->AddActuator("Talon", GetChannel(), this);
+}
diff --git a/wpilibc/athena/src/TalonSRX.cpp b/wpilibc/athena/src/TalonSRX.cpp
new file mode 100644
index 0000000..71b1b02
--- /dev/null
+++ b/wpilibc/athena/src/TalonSRX.cpp
@@ -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 "TalonSRX.h"
+
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.h"
+
+using namespace frc;
+
+/**
+ * Construct a TalonSRX connected via PWM.
+ *
+ * @param channel The PWM channel that the TalonSRX is attached to. 0-9 are
+ *                on-board, 10-19 are on the MXP port
+ */
+TalonSRX::TalonSRX(int channel) : PWMSpeedController(channel) {
+  /* Note that the TalonSRX uses the following bounds for PWM values. These
+   * values should work reasonably well for most controllers, but if users
+   * experience issues such as asymmetric behavior around the deadband or
+   * inability to saturate the controller in either direction, calibration is
+   * recommended. The calibration procedure can be found in the TalonSRX User
+   * Manual available from Cross The Road Electronics.
+   *   2.004ms = full "forward"
+   *   1.52ms = the "high end" of the deadband range
+   *   1.50ms = center of the deadband range (off)
+   *   1.48ms = the "low end" of the deadband range
+   *   0.997ms = full "reverse"
+   */
+  SetBounds(2.004, 1.52, 1.50, 1.48, .997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_TalonSRX, GetChannel());
+  LiveWindow::GetInstance()->AddActuator("TalonSRX", GetChannel(), this);
+}
diff --git a/wpilibc/athena/src/Task.cpp b/wpilibc/athena/src/Task.cpp
new file mode 100644
index 0000000..e7dbc9a
--- /dev/null
+++ b/wpilibc/athena/src/Task.cpp
@@ -0,0 +1,140 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Task.h"
+
+#include <signal.h>
+
+#include <cerrno>
+
+#include "WPIErrors.h"
+
+namespace frc {
+
+const int Task::kDefaultPriority;
+
+Task& Task::operator=(Task&& task) {
+  m_thread.swap(task.m_thread);
+  m_taskName = std::move(task.m_taskName);
+
+  return *this;
+}
+
+Task::~Task() {
+  if (m_thread.joinable()) {
+    std::cout << "[HAL] Exited task " << m_taskName << std::endl;
+  }
+}
+
+bool Task::joinable() const noexcept { return m_thread.joinable(); }
+
+void Task::join() { m_thread.join(); }
+
+void Task::detach() { m_thread.detach(); }
+
+std::thread::id Task::get_id() const noexcept { return m_thread.get_id(); }
+
+std::thread::native_handle_type Task::native_handle() {
+  return m_thread.native_handle();
+}
+
+/**
+ * Verifies a task still exists.
+ *
+ * @return true on success.
+ */
+bool Task::Verify() { return VerifyTaskId() == TASK_OK; }
+
+/**
+ * Gets the priority of a task.
+ *
+ * @return task priority or 0 if an error occured
+ */
+int Task::GetPriority() {
+  int priority;
+  if (HandleError(GetTaskPriority(&priority)))
+    return priority;
+  else
+    return 0;
+}
+
+/**
+ * This routine changes a task's priority to a specified priority.
+ * Priorities range from 1, the lowest priority, to 99, the highest priority.
+ * Default task priority is 60.
+ *
+ * @param priority The priority at which the internal thread should run.
+ * @return true on success.
+ */
+bool Task::SetPriority(int priority) {
+  return HandleError(SetTaskPriority(priority));
+}
+
+/**
+ * Returns the name of the task.
+ *
+ * @return The name of the task.
+ */
+std::string Task::GetName() const { return m_taskName; }
+
+Task::TASK_STATUS Task::VerifyTaskId() {
+  auto task = m_thread.native_handle();
+  if (pthread_kill(task, 0) == 0) {
+    return TASK_OK;
+  } else {
+    return TASK_ERROR;
+  }
+}
+
+Task::TASK_STATUS Task::GetTaskPriority(int32_t* priority) {
+  auto task = m_thread.native_handle();
+  int32_t policy = 0;
+  struct sched_param param;
+
+  if (VerifyTaskId() == TASK_OK &&
+      pthread_getschedparam(task, &policy, &param) == 0) {
+    *priority = param.sched_priority;
+    return TASK_OK;
+  } else {
+    return TASK_ERROR;
+  }
+}
+
+Task::TASK_STATUS Task::SetTaskPriority(int32_t priority) {
+  auto task = m_thread.native_handle();
+  int32_t policy = 0;
+  struct sched_param param;
+
+  if (VerifyTaskId() == TASK_OK &&
+      pthread_getschedparam(task, &policy, &param) == 0) {
+    param.sched_priority = priority;
+    if (pthread_setschedparam(task, SCHED_FIFO, &param) == 0) {
+      return TASK_OK;
+    } else {
+      return TASK_ERROR;
+    }
+  } else {
+    return TASK_ERROR;
+  }
+}
+
+/**
+ * Handles errors generated by task related code.
+ */
+bool Task::HandleError(TASK_STATUS results) {
+  if (results != TASK_ERROR) return true;
+  int errsv = errno;
+  if (errsv == TaskLib_ILLEGAL_PRIORITY) {
+    wpi_setWPIErrorWithContext(TaskPriorityError, m_taskName.c_str());
+  } else {
+    std::printf("ERROR: errno=%i", errsv);
+    wpi_setWPIErrorWithContext(TaskError, m_taskName.c_str());
+  }
+  return false;
+}
+
+}  // namespace frc
diff --git a/wpilibc/athena/src/Threads.cpp b/wpilibc/athena/src/Threads.cpp
new file mode 100644
index 0000000..2ac0f65
--- /dev/null
+++ b/wpilibc/athena/src/Threads.cpp
@@ -0,0 +1,82 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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/Threads.h"
+#include "Threads.h"
+
+#include "ErrorBase.h"
+#include "HAL/HAL.h"
+
+namespace frc {
+/**
+ * Get the thread priority for the specified thread.
+ *
+ * @param thread Reference to the thread to get the priority for
+ * @param isRealTime Set to true if thread is realtime, otherwise false
+ * @return The current thread priority. Scaled 1-99, with 1 being highest.
+ */
+int GetThreadPriority(std::thread& thread, bool* isRealTime) {
+  int32_t status = 0;
+  HAL_Bool rt = false;
+  auto native = thread.native_handle();
+  auto ret = HAL_GetThreadPriority(&native, &rt, &status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  *isRealTime = rt;
+  return ret;
+}
+
+/**
+ * Get the thread priority for the current thread
+ *
+ * @param isRealTime Set to true if thread is realtime, otherwise false
+ * @return The current thread priority. Scaled 1-99.
+ */
+int GetCurrentThreadPriority(bool* isRealTime) {
+  int32_t status = 0;
+  HAL_Bool rt = false;
+  auto ret = HAL_GetCurrentThreadPriority(&rt, &status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  *isRealTime = rt;
+  return ret;
+}
+
+/**
+ * Sets the thread priority for the specified thread
+ *
+ * @param thread Reference to the thread to set the priority of
+ * @param realTime Set to true to set a realtime priority, false for standard
+ * priority
+ * @param priority Priority to set the thread to. Scaled 1-99, with 1 being
+ * highest. On RoboRIO, priority is ignored for non realtime setting
+ *
+ * @return The success state of setting the priority
+ */
+bool SetThreadPriority(std::thread& thread, bool realTime, int priority) {
+  int32_t status = 0;
+  auto native = thread.native_handle();
+  auto ret = HAL_SetThreadPriority(&native, realTime, priority, &status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return ret;
+}
+
+/**
+ * Sets the thread priority for the current thread
+ *
+ * @param realTime Set to true to set a realtime priority, false for standard
+ * priority
+ * @param priority Priority to set the thread to. Scaled 1-99, with 1 being
+ * highest. On RoboRIO, priority is ignored for non realtime setting
+ *
+ * @return The success state of setting the priority
+ */
+bool SetCurrentThreadPriority(bool realTime, int priority) {
+  int32_t status = 0;
+  auto ret = HAL_SetCurrentThreadPriority(realTime, priority, &status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return ret;
+}
+}  // namespace frc
diff --git a/wpilibc/athena/src/Timer.cpp b/wpilibc/athena/src/Timer.cpp
new file mode 100644
index 0000000..04e7428
--- /dev/null
+++ b/wpilibc/athena/src/Timer.cpp
@@ -0,0 +1,191 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Timer.h"
+
+#include <chrono>
+#include <iostream>
+#include <thread>
+
+#include "DriverStation.h"
+#include "HAL/HAL.h"
+#include "Utility.h"
+
+namespace frc {
+
+/**
+ * Pause the task for a specified time.
+ *
+ * Pause the execution of the program for a specified period of time given in
+ * seconds. Motors will continue to run at their last assigned values, and
+ * sensors will continue to update. Only the task containing the wait will
+ * pause until the wait time is expired.
+ *
+ * @param seconds Length of time to pause, in seconds.
+ */
+void Wait(double seconds) {
+  if (seconds < 0.0) return;
+  std::this_thread::sleep_for(std::chrono::duration<double>(seconds));
+}
+
+/**
+ * Return the FPGA system clock time in seconds.
+ * This is deprecated and just forwards to Timer::GetFPGATimestamp().
+ * @return Robot running time in seconds.
+ */
+double GetClock() { return Timer::GetFPGATimestamp(); }
+
+/**
+ * @brief Gives real-time clock system time with nanosecond resolution
+ * @return The time, just in case you want the robot to start autonomous at 8pm
+ *         on Saturday.
+ */
+double GetTime() {
+  using namespace std::chrono;
+  return duration_cast<duration<double>>(system_clock::now().time_since_epoch())
+      .count();
+}
+
+}  // namespace frc
+
+using namespace frc;
+
+// for compatibility with msvc12--see C2864
+const double Timer::kRolloverTime = (1ll << 32) / 1e6;
+/**
+ * Create a new timer object.
+ *
+ * Create a new timer object and reset the time to zero. The timer is initially
+ * not running and
+ * must be started.
+ */
+Timer::Timer() {
+  // Creates a semaphore to control access to critical regions.
+  // Initially 'open'
+  Reset();
+}
+
+/**
+ * Get the current time from the timer. If the clock is running it is derived
+ * from the current system clock the start time stored in the timer class. If
+ * the clock is not running, then return the time when it was last stopped.
+ *
+ * @return Current time value for this timer in seconds
+ */
+double Timer::Get() const {
+  double result;
+  double currentTime = GetFPGATimestamp();
+
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  if (m_running) {
+    // If the current time is before the start time, then the FPGA clock
+    // rolled over.  Compensate by adding the ~71 minutes that it takes
+    // to roll over to the current time.
+    if (currentTime < m_startTime) {
+      currentTime += kRolloverTime;
+    }
+
+    result = (currentTime - m_startTime) + m_accumulatedTime;
+  } else {
+    result = m_accumulatedTime;
+  }
+
+  return result;
+}
+
+/**
+ * Reset the timer by setting the time to 0.
+ *
+ * Make the timer startTime the current time so new requests will be relative to
+ * now.
+ */
+void Timer::Reset() {
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  m_accumulatedTime = 0;
+  m_startTime = GetFPGATimestamp();
+}
+
+/**
+ * Start the timer running.
+ *
+ * Just set the running flag to true indicating that all time requests should be
+ * relative to the system clock.
+ */
+void Timer::Start() {
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  if (!m_running) {
+    m_startTime = GetFPGATimestamp();
+    m_running = true;
+  }
+}
+
+/**
+ * Stop the timer.
+ *
+ * This computes the time as of now and clears the running flag, causing all
+ * subsequent time requests to be read from the accumulated time rather than
+ * looking at the system clock.
+ */
+void Timer::Stop() {
+  double temp = Get();
+
+  std::lock_guard<priority_mutex> sync(m_mutex);
+  if (m_running) {
+    m_accumulatedTime = temp;
+    m_running = false;
+  }
+}
+
+/**
+ * Check if the period specified has passed and if it has, advance the start
+ * time by that period. This is useful to decide if it's time to do periodic
+ * work without drifting later by the time it took to get around to checking.
+ *
+ * @param period The period to check for (in seconds).
+ * @return True if the period has passed.
+ */
+bool Timer::HasPeriodPassed(double period) {
+  if (Get() > period) {
+    std::lock_guard<priority_mutex> sync(m_mutex);
+    // Advance the start time by the period.
+    m_startTime += period;
+    // Don't set it to the current time... we want to avoid drift.
+    return true;
+  }
+  return false;
+}
+
+/**
+ * Return the FPGA system clock time in seconds.
+ *
+ * Return the time from the FPGA hardware clock in seconds since the FPGA
+ * started. Rolls over after 71 minutes.
+ *
+ * @returns Robot running time in seconds.
+ */
+double Timer::GetFPGATimestamp() {
+  // FPGA returns the timestamp in microseconds
+  // Call the helper GetFPGATime() in Utility.cpp
+  return GetFPGATime() * 1.0e-6;
+}
+
+/**
+ * Return the approximate match time The FMS does not currently send the
+ * official match time to
+ * the robots This returns the time since the enable signal sent from the Driver
+ * Station At the
+ * beginning of autonomous, the time is reset to 0.0 seconds At the beginning of
+ * teleop, the time
+ * is reset to +15.0 seconds If the robot is disabled, this returns 0.0 seconds
+ * Warning: This is
+ * not an official time (so it cannot be used to argue with referees).
+ *
+ * @return Match time in seconds since the beginning of autonomous
+ */
+double Timer::GetMatchTime() {
+  return DriverStation::GetInstance().GetMatchTime();
+}
diff --git a/wpilibc/athena/src/Ultrasonic.cpp b/wpilibc/athena/src/Ultrasonic.cpp
new file mode 100644
index 0000000..4b3549e
--- /dev/null
+++ b/wpilibc/athena/src/Ultrasonic.cpp
@@ -0,0 +1,337 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Ultrasonic.h"
+
+#include "Counter.h"
+#include "DigitalInput.h"
+#include "DigitalOutput.h"
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.h"
+#include "Timer.h"
+#include "Utility.h"
+#include "WPIErrors.h"
+
+using namespace frc;
+
+// Time (sec) for the ping trigger pulse.
+constexpr double Ultrasonic::kPingTime;
+// Priority that the ultrasonic round robin task runs.
+const int Ultrasonic::kPriority;
+// Max time (ms) between readings.
+constexpr double Ultrasonic::kMaxUltrasonicTime;
+constexpr double Ultrasonic::kSpeedOfSoundInchesPerSec;
+// automatic round robin mode
+std::atomic<bool> Ultrasonic::m_automaticEnabled{false};
+std::set<Ultrasonic*> Ultrasonic::m_sensors;
+std::thread Ultrasonic::m_thread;
+
+/**
+ * Background task that goes through the list of ultrasonic sensors and pings
+ * each one in turn. The counter is configured to read the timing of the
+ * returned echo pulse.
+ *
+ * DANGER WILL ROBINSON, DANGER WILL ROBINSON:
+ * This code runs as a task and assumes that none of the ultrasonic sensors
+ * will change while it's running. Make sure to disable automatic mode before
+ * touching the list.
+ */
+void Ultrasonic::UltrasonicChecker() {
+  while (m_automaticEnabled) {
+    for (auto& sensor : m_sensors) {
+      if (!m_automaticEnabled) break;
+
+      if (sensor->IsEnabled()) {
+        sensor->m_pingChannel->Pulse(kPingTime);  // do the ping
+      }
+
+      Wait(0.1);  // wait for ping to return
+    }
+  }
+}
+
+/**
+ * Initialize the Ultrasonic Sensor.
+ *
+ * This is the common code that initializes the ultrasonic sensor given that
+ * there are two digital I/O channels allocated. If the system was running in
+ * automatic mode (round robin) when the new sensor is added, it is stopped,
+ * the sensor is added, then automatic mode is restored.
+ */
+void Ultrasonic::Initialize() {
+  bool originalMode = m_automaticEnabled;
+  SetAutomaticMode(false);  // kill task when adding a new sensor
+  // link this instance on the list
+  m_sensors.insert(this);
+
+  m_counter.SetMaxPeriod(1.0);
+  m_counter.SetSemiPeriodMode(true);
+  m_counter.Reset();
+  m_enabled = true;  // make it available for round robin scheduling
+  SetAutomaticMode(originalMode);
+
+  static int instances = 0;
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_Ultrasonic, instances);
+  LiveWindow::GetInstance()->AddSensor("Ultrasonic",
+                                       m_echoChannel->GetChannel(), this);
+}
+
+/**
+ * Create an instance of the Ultrasonic Sensor.
+ *
+ * This is designed to support the Daventech SRF04 and Vex ultrasonic
+ * sensors.
+ *
+ * @param pingChannel The digital output channel that sends the pulse to
+ *                    initiate the sensor sending the ping.
+ * @param echoChannel The digital input channel that receives the echo. The
+ *                    length of time that the echo is high represents the
+ *                    round trip time of the ping, and the distance.
+ * @param units       The units returned in either kInches or kMilliMeters
+ */
+Ultrasonic::Ultrasonic(int pingChannel, int echoChannel, DistanceUnit units)
+    : m_pingChannel(std::make_shared<DigitalOutput>(pingChannel)),
+      m_echoChannel(std::make_shared<DigitalInput>(echoChannel)),
+      m_counter(m_echoChannel) {
+  m_units = units;
+  Initialize();
+}
+
+/**
+ * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
+ * channel and a DigitalOutput for the ping channel.
+ *
+ * @param pingChannel The digital output object that starts the sensor doing a
+ *                    ping. Requires a 10uS pulse to start.
+ * @param echoChannel The digital input object that times the return pulse to
+ *                    determine the range.
+ * @param units       The units returned in either kInches or kMilliMeters
+ */
+Ultrasonic::Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel,
+                       DistanceUnit units)
+    : m_pingChannel(pingChannel, NullDeleter<DigitalOutput>()),
+      m_echoChannel(echoChannel, NullDeleter<DigitalInput>()),
+      m_counter(m_echoChannel) {
+  if (pingChannel == nullptr || echoChannel == nullptr) {
+    wpi_setWPIError(NullParameter);
+    m_units = units;
+    return;
+  }
+  m_units = units;
+  Initialize();
+}
+
+/**
+ * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
+ * channel and a DigitalOutput for the ping channel.
+ *
+ * @param pingChannel The digital output object that starts the sensor doing a
+ *                    ping. Requires a 10uS pulse to start.
+ * @param echoChannel The digital input object that times the return pulse to
+ *                    determine the range.
+ * @param units       The units returned in either kInches or kMilliMeters
+ */
+Ultrasonic::Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel,
+                       DistanceUnit units)
+    : m_pingChannel(&pingChannel, NullDeleter<DigitalOutput>()),
+      m_echoChannel(&echoChannel, NullDeleter<DigitalInput>()),
+      m_counter(m_echoChannel) {
+  m_units = units;
+  Initialize();
+}
+
+/**
+ * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
+ * channel and a DigitalOutput for the ping channel.
+ *
+ * @param pingChannel The digital output object that starts the sensor doing a
+ *                    ping. Requires a 10uS pulse to start.
+ * @param echoChannel The digital input object that times the return pulse to
+ *                    determine the range.
+ * @param units       The units returned in either kInches or kMilliMeters
+ */
+Ultrasonic::Ultrasonic(std::shared_ptr<DigitalOutput> pingChannel,
+                       std::shared_ptr<DigitalInput> echoChannel,
+                       DistanceUnit units)
+    : m_pingChannel(pingChannel),
+      m_echoChannel(echoChannel),
+      m_counter(m_echoChannel) {
+  m_units = units;
+  Initialize();
+}
+
+/**
+ * Destructor for the ultrasonic sensor.
+ *
+ * Delete the instance of the ultrasonic sensor by freeing the allocated digital
+ * channels. If the system was in automatic mode (round robin), then it is
+ * stopped, then started again after this sensor is removed (provided this
+ * wasn't the last sensor).
+ */
+Ultrasonic::~Ultrasonic() {
+  bool wasAutomaticMode = m_automaticEnabled;
+  SetAutomaticMode(false);
+
+  // No synchronization needed because the background task is stopped.
+  m_sensors.erase(this);
+
+  if (!m_sensors.empty() && wasAutomaticMode) {
+    SetAutomaticMode(true);
+  }
+}
+
+/**
+ * Turn Automatic mode on/off.
+ *
+ * When in Automatic mode, all sensors will fire in round robin, waiting a set
+ * time between each sensor.
+ *
+ * @param enabling Set to true if round robin scheduling should start for all
+ *                 the ultrasonic sensors. This scheduling method assures that
+ *                 the sensors are non-interfering because no two sensors fire
+ *                 at the same time. If another scheduling algorithm is
+ *                 prefered, it can be implemented by pinging the sensors
+ *                 manually and waiting for the results to come back.
+ */
+void Ultrasonic::SetAutomaticMode(bool enabling) {
+  if (enabling == m_automaticEnabled) return;  // ignore the case of no change
+
+  m_automaticEnabled = enabling;
+
+  if (enabling) {
+    /* Clear all the counters so no data is valid. No synchronization is needed
+     * because the background task is stopped.
+     */
+    for (auto& sensor : m_sensors) {
+      sensor->m_counter.Reset();
+    }
+
+    m_thread = std::thread(&Ultrasonic::UltrasonicChecker);
+
+    // TODO: Currently, lvuser does not have permissions to set task priorities.
+    // Until that is the case, uncommenting this will break user code that calls
+    // Ultrasonic::SetAutomicMode().
+    // m_task.SetPriority(kPriority);
+  } else {
+    // Wait for background task to stop running
+    m_thread.join();
+
+    /* Clear all the counters (data now invalid) since automatic mode is
+     * disabled. No synchronization is needed because the background task is
+     * stopped.
+     */
+    for (auto& sensor : m_sensors) {
+      sensor->m_counter.Reset();
+    }
+  }
+}
+
+/**
+ * Single ping to ultrasonic sensor.
+ *
+ * Send out a single ping to the ultrasonic sensor. This only works if automatic
+ * (round robin) mode is disabled. A single ping is sent out, and the counter
+ * should count the semi-period when it comes in. The counter is reset to make
+ * the current value invalid.
+ */
+void Ultrasonic::Ping() {
+  wpi_assert(!m_automaticEnabled);
+  m_counter.Reset();  // reset the counter to zero (invalid data now)
+  m_pingChannel->Pulse(
+      kPingTime);  // do the ping to start getting a single range
+}
+
+/**
+ * Check if there is a valid range measurement.
+ *
+ * The ranges are accumulated in a counter that will increment on each edge of
+ * the echo (return) signal. If the count is not at least 2, then the range has
+ * not yet been measured, and is invalid.
+ */
+bool Ultrasonic::IsRangeValid() const { return m_counter.Get() > 1; }
+
+/**
+ * Get the range in inches from the ultrasonic sensor.
+ *
+ * @return double Range in inches of the target returned from the ultrasonic
+ *         sensor. If there is no valid value yet, i.e. at least one
+ *         measurement hasn't completed, then return 0.
+ */
+double Ultrasonic::GetRangeInches() const {
+  if (IsRangeValid())
+    return m_counter.GetPeriod() * kSpeedOfSoundInchesPerSec / 2.0;
+  else
+    return 0;
+}
+
+/**
+ * Get the range in millimeters from the ultrasonic sensor.
+ *
+ * @return double Range in millimeters of the target returned by the ultrasonic
+ *         sensor. If there is no valid value yet, i.e. at least one
+ *         measurement hasn't completed, then return 0.
+ */
+double Ultrasonic::GetRangeMM() const { return GetRangeInches() * 25.4; }
+
+/**
+ * Get the range in the current DistanceUnit for the PIDSource base object.
+ *
+ * @return The range in DistanceUnit
+ */
+double Ultrasonic::PIDGet() {
+  switch (m_units) {
+    case Ultrasonic::kInches:
+      return GetRangeInches();
+    case Ultrasonic::kMilliMeters:
+      return GetRangeMM();
+    default:
+      return 0.0;
+  }
+}
+
+void Ultrasonic::SetPIDSourceType(PIDSourceType pidSource) {
+  if (wpi_assert(pidSource == PIDSourceType::kDisplacement)) {
+    m_pidSource = pidSource;
+  }
+}
+
+/**
+ * Set the current DistanceUnit that should be used for the PIDSource base
+ * object.
+ *
+ * @param units The DistanceUnit that should be used.
+ */
+void Ultrasonic::SetDistanceUnits(DistanceUnit units) { m_units = units; }
+
+/**
+ * Get the current DistanceUnit that is used for the PIDSource base object.
+ *
+ * @return The type of DistanceUnit that is being used.
+ */
+Ultrasonic::DistanceUnit Ultrasonic::GetDistanceUnits() const {
+  return m_units;
+}
+
+void Ultrasonic::UpdateTable() {
+  if (m_table != nullptr) {
+    m_table->PutNumber("Value", GetRangeInches());
+  }
+}
+
+void Ultrasonic::StartLiveWindowMode() {}
+
+void Ultrasonic::StopLiveWindowMode() {}
+
+std::string Ultrasonic::GetSmartDashboardType() const { return "Ultrasonic"; }
+
+void Ultrasonic::InitTable(std::shared_ptr<ITable> subTable) {
+  m_table = subTable;
+  UpdateTable();
+}
+
+std::shared_ptr<ITable> Ultrasonic::GetTable() const { return m_table; }
diff --git a/wpilibc/athena/src/Utility.cpp b/wpilibc/athena/src/Utility.cpp
new file mode 100644
index 0000000..741691a
--- /dev/null
+++ b/wpilibc/athena/src/Utility.cpp
@@ -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 "Utility.h"
+
+#include <cxxabi.h>
+#include <execinfo.h>
+
+#include <cstdio>
+#include <cstdlib>
+#include <cstring>
+#include <sstream>
+
+#include "ErrorBase.h"
+#include "HAL/DriverStation.h"
+#include "HAL/HAL.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/wpilibc/athena/src/Victor.cpp b/wpilibc/athena/src/Victor.cpp
new file mode 100644
index 0000000..d06f091
--- /dev/null
+++ b/wpilibc/athena/src/Victor.cpp
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Victor.h"
+
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.h"
+
+using namespace frc;
+
+/**
+ * Constructor for a Victor.
+ *
+ * @param channel The PWM channel number that the Victor is attached to. 0-9
+ *                are on-board, 10-19 are on the MXP port
+ */
+Victor::Victor(int channel) : PWMSpeedController(channel) {
+  /* Note that the Victor uses the following bounds for PWM values.  These
+   * values were determined empirically and optimized for the Victor 888. These
+   * values should work reasonably well for Victor 884 controllers as well but
+   * if users experience issues such as asymmetric behaviour around the deadband
+   * or inability to saturate the controller in either direction, calibration is
+   * recommended. The calibration procedure can be found in the Victor 884 User
+   * Manual available from IFI.
+   *
+   *   2.027ms = full "forward"
+   *   1.525ms = the "high end" of the deadband range
+   *   1.507ms = center of the deadband range (off)
+   *   1.49ms = the "low end" of the deadband range
+   *   1.026ms = full "reverse"
+   */
+  SetBounds(2.027, 1.525, 1.507, 1.49, 1.026);
+  SetPeriodMultiplier(kPeriodMultiplier_2X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  LiveWindow::GetInstance()->AddActuator("Victor", GetChannel(), this);
+  HAL_Report(HALUsageReporting::kResourceType_Victor, GetChannel());
+}
diff --git a/wpilibc/athena/src/VictorSP.cpp b/wpilibc/athena/src/VictorSP.cpp
new file mode 100644
index 0000000..a1335d6
--- /dev/null
+++ b/wpilibc/athena/src/VictorSP.cpp
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "VictorSP.h"
+
+#include "HAL/HAL.h"
+#include "LiveWindow/LiveWindow.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) : PWMSpeedController(channel) {
+  /**
+   * Note that the VictorSP uses the following bounds for PWM values. These
+   * values should work reasonably well for most controllers, but if users
+   * experience issues such as asymmetric behavior around the deadband or
+   * inability to saturate the controller in either direction, calibration is
+   * recommended. The calibration procedure can be found in the VictorSP User
+   * Manual available from Vex.
+   *
+   *   2.004ms = full "forward"
+   *   1.52ms = the "high end" of the deadband range
+   *   1.50ms = center of the deadband range (off)
+   *   1.48ms = the "low end" of the deadband range
+   *   0.997ms = full "reverse"
+   */
+  SetBounds(2.004, 1.52, 1.50, 1.48, .997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_VictorSP, GetChannel());
+  LiveWindow::GetInstance()->AddActuator("VictorSP", GetChannel(), this);
+}
diff --git a/wpilibc/athena/src/XboxController.cpp b/wpilibc/athena/src/XboxController.cpp
new file mode 100644
index 0000000..aa494dd
--- /dev/null
+++ b/wpilibc/athena/src/XboxController.cpp
@@ -0,0 +1,141 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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 "XboxController.h"
+
+#include "DriverStation.h"
+#include "HAL/HAL.h"
+
+using namespace frc;
+
+/**
+ * Construct an instance of an Xbox controller.
+ *
+ * The joystick index is the USB port on the Driver Station.
+ *
+ * @param port The port on the Driver Station that the joystick is plugged into
+ *             (0-5).
+ */
+XboxController::XboxController(int port)
+    : GamepadBase(port), m_ds(DriverStation::GetInstance()) {
+  // HAL_Report(HALUsageReporting::kResourceType_XboxController, port);
+  HAL_Report(HALUsageReporting::kResourceType_Joystick, port);
+}
+
+/**
+ * Get the X axis value of the controller.
+ *
+ * @param hand Side of controller whose value should be returned.
+ */
+double XboxController::GetX(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawAxis(0);
+  } else {
+    return GetRawAxis(4);
+  }
+}
+
+/**
+ * Get the Y axis value of the controller.
+ *
+ * @param hand Side of controller whose value should be returned.
+ */
+double XboxController::GetY(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawAxis(1);
+  } else {
+    return GetRawAxis(5);
+  }
+}
+
+/**
+ * Read the value of the bumper button on the controller.
+ *
+ * @param hand Side of controller whose value should be returned.
+ */
+bool XboxController::GetBumper(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawButton(5);
+  } else {
+    return GetRawButton(6);
+  }
+}
+
+/**
+ * Read the value of the stick button on the controller.
+ *
+ * @param hand Side of controller whose value should be returned.
+ * @return The state of the button.
+ */
+bool XboxController::GetStickButton(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawButton(9);
+  } else {
+    return GetRawButton(10);
+  }
+}
+
+/**
+ * Get the trigger axis value of the controller.
+ *
+ * @param hand Side of controller whose value should be returned.
+ */
+double XboxController::GetTriggerAxis(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawAxis(2);
+  } else {
+    return GetRawAxis(3);
+  }
+}
+
+/**
+ * Read the value of the A button on the controller.
+ *
+ * @param hand Side of controller whose value should be returned.
+ * @return The state of the button.
+ */
+bool XboxController::GetAButton() const { return GetRawButton(1); }
+
+/**
+ * Read the value of the B button on the controller.
+ *
+ * @param hand Side of controller whose value should be returned.
+ * @return The state of the button.
+ */
+bool XboxController::GetBButton() const { return GetRawButton(2); }
+
+/**
+ * Read the value of the X button on the controller.
+ *
+ * @param hand Side of controller whose value should be returned.
+ * @return The state of the button.
+ */
+bool XboxController::GetXButton() const { return GetRawButton(3); }
+
+/**
+ * Read the value of the Y button on the controller.
+ *
+ * @param hand Side of controller whose value should be returned.
+ * @return The state of the button.
+ */
+bool XboxController::GetYButton() const { return GetRawButton(4); }
+
+/**
+ * Read the value of the back button on the controller.
+ *
+ * @param hand Side of controller whose value should be returned.
+ * @return The state of the button.
+ */
+bool XboxController::GetBackButton() const { return GetRawButton(7); }
+
+/**
+ * Read the value of the start button on the controller.
+ *
+ * @param hand Side of controller whose value should be returned.
+ * @return The state of the button.
+ */
+bool XboxController::GetStartButton() const { return GetRawButton(8); }
diff --git a/wpilibc/athena/src/vision/VisionRunner.cpp b/wpilibc/athena/src/vision/VisionRunner.cpp
new file mode 100644
index 0000000..493c29e
--- /dev/null
+++ b/wpilibc/athena/src/vision/VisionRunner.cpp
@@ -0,0 +1,76 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2016-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 "vision/VisionRunner.h"
+
+#include "DriverStation.h"
+#include "RobotBase.h"
+#include "opencv2/core/mat.hpp"
+
+using namespace frc;
+
+/**
+ * Creates a new vision runner. It will take images from the {@code
+ * videoSource}, and call the virtual DoProcess() method.
+ *
+ * @param videoSource the video source to use to supply images for the pipeline
+ */
+VisionRunnerBase::VisionRunnerBase(cs::VideoSource videoSource)
+    : m_image(std::make_unique<cv::Mat>()), m_cvSink("VisionRunner CvSink") {
+  m_cvSink.SetSource(videoSource);
+}
+
+// Located here and not in header due to cv::Mat forward declaration.
+VisionRunnerBase::~VisionRunnerBase() {}
+
+/**
+ * Runs the pipeline one time, giving it the next image from the video source
+ * specified in the constructor. This will block until the source either has an
+ * image or throws an error. If the source successfully supplied a frame, the
+ * pipeline's image input will be set, the pipeline will run, and the listener
+ * specified in the constructor will be called to notify it that the pipeline
+ * ran. This must be run in a dedicated thread, and cannot be used in the main
+ * robot thread because it will freeze the robot program.
+ *
+ * <p>This method is exposed to allow teams to add additional functionality or
+ * have their own ways to run the pipeline. Most teams, however, should just
+ * use {@link #runForever} in its own thread using a std::thread.</p>
+ */
+void VisionRunnerBase::RunOnce() {
+  if (std::this_thread::get_id() == RobotBase::GetThreadId()) {
+    wpi_setErrnoErrorWithContext(
+        "VisionRunner::RunOnce() cannot be called from the main robot thread");
+    return;
+  }
+  auto frameTime = m_cvSink.GrabFrame(*m_image);
+  if (frameTime == 0) {
+    auto error = m_cvSink.GetError();
+    DriverStation::ReportError(error);
+  } else {
+    DoProcess(*m_image);
+  }
+}
+
+/**
+ * A convenience method that calls {@link #runOnce()} in an infinite loop. This
+ * must be run in a dedicated thread, and cannot be used in the main robot
+ * thread because it will freeze the robot program.
+ *
+ * <p><strong>Do not call this method directly from the main
+ * thread.</strong></p>
+ */
+void VisionRunnerBase::RunForever() {
+  if (std::this_thread::get_id() == RobotBase::GetThreadId()) {
+    wpi_setErrnoErrorWithContext(
+        "VisionRunner::RunForever() cannot be called from the main robot "
+        "thread");
+    return;
+  }
+  while (true) {
+    RunOnce();
+  }
+}