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