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/shared/include/Base.h b/wpilibc/shared/include/Base.h
new file mode 100644
index 0000000..8374d2a
--- /dev/null
+++ b/wpilibc/shared/include/Base.h
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "HAL/cpp/make_unique.h"
+
+// MSVC 2013 doesn't allow "= default" on move constructors, but since we are
+// (currently) only actually using the move constructors in non-MSVC situations
+// (ie, wpilibC++Devices), we can just ignore it in MSVC.
+#if !defined(_MSC_VER)
+#define DEFAULT_MOVE_CONSTRUCTOR(ClassName) ClassName(ClassName&&) = default
+#else
+#define DEFAULT_MOVE_CONSTRUCTOR(ClassName)
+#endif
+
+#if (__cplusplus < 201103L)
+#if !defined(_MSC_VER)
+#define nullptr NULL
+#endif
+#define constexpr const
+#endif
+
+#if defined(_MSC_VER)
+#define noexcept throw()
+#endif
+
+// Provide std::decay_t when using GCC < 4.9
+#if defined(__GNUC__)
+#if __GNUC__ == 4 && __GNUC_MINOR__ < 9
+#include <type_traits>
+namespace std {
+template <class T>
+using decay_t = typename decay<T>::type;
+}
+#endif
+#endif
+
+namespace frc {
+
+// A struct to use as a deleter when a std::shared_ptr must wrap a raw pointer
+// that is being deleted by someone else.
+template <class T>
+struct NullDeleter {
+  void operator()(T*) const noexcept {};
+};
+
+}  // namespace frc
+
+#include <atomic>
+
+namespace frc {
+
+// Use this for determining whether the default move constructor has been
+// called on a containing object. This serves the purpose of allowing us to
+// use the default move constructor of an object for moving all the data around
+// while being able to use this to, for instance, chose not to de-allocate
+// a PWM port in a destructor.
+struct HasBeenMoved {
+  HasBeenMoved(HasBeenMoved&& other) {
+    other.moved = true;
+    moved = false;
+  }
+  HasBeenMoved() = default;
+  std::atomic<bool> moved{false};
+  operator bool() const { return moved; }
+};
+
+}  // namespace frc
+
+// For backwards compatibility
+#ifndef NAMESPACED_WPILIB
+using namespace frc;  // NOLINT
+#endif
diff --git a/wpilibc/shared/include/Buttons/Button.h b/wpilibc/shared/include/Buttons/Button.h
new file mode 100644
index 0000000..12b4fce
--- /dev/null
+++ b/wpilibc/shared/include/Buttons/Button.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Buttons/Trigger.h"
+#include "Commands/Command.h"
+
+namespace frc {
+
+/**
+ * This class provides an easy way to link commands to OI inputs.
+ *
+ * It is very easy to link a button to a command.  For instance, you could
+ * link the trigger button of a joystick to a "score" command.
+ *
+ * This class represents a subclass of Trigger that is specifically aimed at
+ * buttons on an operator interface as a common use case of the more generalized
+ * Trigger objects. This is a simple wrapper around Trigger with the method
+ * names
+ * renamed to fit the Button object use.
+ */
+class Button : public Trigger {
+ public:
+  virtual void WhenPressed(Command* command);
+  virtual void WhileHeld(Command* command);
+  virtual void WhenReleased(Command* command);
+  virtual void CancelWhenPressed(Command* command);
+  virtual void ToggleWhenPressed(Command* command);
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Buttons/ButtonScheduler.h b/wpilibc/shared/include/Buttons/ButtonScheduler.h
new file mode 100644
index 0000000..45c0204
--- /dev/null
+++ b/wpilibc/shared/include/Buttons/ButtonScheduler.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* 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 Trigger;
+class Command;
+
+class ButtonScheduler {
+ public:
+  ButtonScheduler(bool last, Trigger* button, Command* orders);
+  virtual ~ButtonScheduler() = default;
+  virtual void Execute() = 0;
+  void Start();
+
+ protected:
+  bool m_pressedLast;
+  Trigger* m_button;
+  Command* m_command;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Buttons/CancelButtonScheduler.h b/wpilibc/shared/include/Buttons/CancelButtonScheduler.h
new file mode 100644
index 0000000..3dd3259
--- /dev/null
+++ b/wpilibc/shared/include/Buttons/CancelButtonScheduler.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Buttons/ButtonScheduler.h"
+
+namespace frc {
+
+class Trigger;
+class Command;
+
+class CancelButtonScheduler : public ButtonScheduler {
+ public:
+  CancelButtonScheduler(bool last, Trigger* button, Command* orders);
+  virtual ~CancelButtonScheduler() = default;
+  virtual void Execute();
+
+ private:
+  bool pressedLast;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Buttons/HeldButtonScheduler.h b/wpilibc/shared/include/Buttons/HeldButtonScheduler.h
new file mode 100644
index 0000000..7cedde3
--- /dev/null
+++ b/wpilibc/shared/include/Buttons/HeldButtonScheduler.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Buttons/ButtonScheduler.h"
+
+namespace frc {
+
+class Trigger;
+class Command;
+
+class HeldButtonScheduler : public ButtonScheduler {
+ public:
+  HeldButtonScheduler(bool last, Trigger* button, Command* orders);
+  virtual ~HeldButtonScheduler() = default;
+  virtual void Execute();
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Buttons/InternalButton.h b/wpilibc/shared/include/Buttons/InternalButton.h
new file mode 100644
index 0000000..9c2fd8f
--- /dev/null
+++ b/wpilibc/shared/include/Buttons/InternalButton.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
+
+#include "Buttons/Button.h"
+
+namespace frc {
+
+class InternalButton : public Button {
+ public:
+  InternalButton() = default;
+  explicit InternalButton(bool inverted);
+  virtual ~InternalButton() = default;
+
+  void SetInverted(bool inverted);
+  void SetPressed(bool pressed);
+
+  virtual bool Get();
+
+ private:
+  bool m_pressed = false;
+  bool m_inverted = false;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Buttons/JoystickButton.h b/wpilibc/shared/include/Buttons/JoystickButton.h
new file mode 100644
index 0000000..5f079b4
--- /dev/null
+++ b/wpilibc/shared/include/Buttons/JoystickButton.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Buttons/Button.h"
+#include "GenericHID.h"
+
+namespace frc {
+
+class JoystickButton : public Button {
+ public:
+  JoystickButton(GenericHID* joystick, int buttonNumber);
+  virtual ~JoystickButton() = default;
+
+  virtual bool Get();
+
+ private:
+  GenericHID* m_joystick;
+  int m_buttonNumber;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Buttons/NetworkButton.h b/wpilibc/shared/include/Buttons/NetworkButton.h
new file mode 100644
index 0000000..9be23b7
--- /dev/null
+++ b/wpilibc/shared/include/Buttons/NetworkButton.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
+
+#include <memory>
+#include <string>
+
+#include "Buttons/Button.h"
+
+namespace frc {
+
+class NetworkButton : public Button {
+ public:
+  NetworkButton(const std::string& tableName, const std::string& field);
+  NetworkButton(std::shared_ptr<ITable> table, const std::string& field);
+  virtual ~NetworkButton() = default;
+
+  virtual bool Get();
+
+ private:
+  std::shared_ptr<ITable> m_netTable;
+  std::string m_field;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Buttons/PressedButtonScheduler.h b/wpilibc/shared/include/Buttons/PressedButtonScheduler.h
new file mode 100644
index 0000000..15b7ec4
--- /dev/null
+++ b/wpilibc/shared/include/Buttons/PressedButtonScheduler.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Buttons/ButtonScheduler.h"
+
+namespace frc {
+
+class Trigger;
+class Command;
+
+class PressedButtonScheduler : public ButtonScheduler {
+ public:
+  PressedButtonScheduler(bool last, Trigger* button, Command* orders);
+  virtual ~PressedButtonScheduler() = default;
+  virtual void Execute();
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Buttons/ReleasedButtonScheduler.h b/wpilibc/shared/include/Buttons/ReleasedButtonScheduler.h
new file mode 100644
index 0000000..34cbd54
--- /dev/null
+++ b/wpilibc/shared/include/Buttons/ReleasedButtonScheduler.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Buttons/ButtonScheduler.h"
+
+namespace frc {
+
+class Trigger;
+class Command;
+
+class ReleasedButtonScheduler : public ButtonScheduler {
+ public:
+  ReleasedButtonScheduler(bool last, Trigger* button, Command* orders);
+  virtual ~ReleasedButtonScheduler() = default;
+  virtual void Execute();
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Buttons/ToggleButtonScheduler.h b/wpilibc/shared/include/Buttons/ToggleButtonScheduler.h
new file mode 100644
index 0000000..b7464c8
--- /dev/null
+++ b/wpilibc/shared/include/Buttons/ToggleButtonScheduler.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Buttons/ButtonScheduler.h"
+
+namespace frc {
+
+class Trigger;
+class Command;
+
+class ToggleButtonScheduler : public ButtonScheduler {
+ public:
+  ToggleButtonScheduler(bool last, Trigger* button, Command* orders);
+  virtual ~ToggleButtonScheduler() = default;
+  virtual void Execute();
+
+ private:
+  bool pressedLast;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Buttons/Trigger.h b/wpilibc/shared/include/Buttons/Trigger.h
new file mode 100644
index 0000000..8ab166c
--- /dev/null
+++ b/wpilibc/shared/include/Buttons/Trigger.h
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <memory>
+#include <string>
+
+#include "SmartDashboard/Sendable.h"
+
+namespace frc {
+
+class Command;
+
+/**
+ * This class provides an easy way to link commands to inputs.
+ *
+ * It is very easy to link a polled input to a command.  For instance, you could
+ * link the trigger button of a joystick to a "score" command or an encoder
+ * reaching
+ * a particular value.
+ *
+ * It is encouraged that teams write a subclass of Trigger if they want to have
+ * something unusual (for instance, if they want to react to the user holding
+ * a button while the robot is reading a certain sensor input).  For this, they
+ * only have to write the {@link Trigger#Get()} method to get the full
+ * functionality
+ * of the Trigger class.
+ */
+class Trigger : public Sendable {
+ public:
+  Trigger() = default;
+  virtual ~Trigger() = default;
+  bool Grab();
+  virtual bool Get() = 0;
+  void WhenActive(Command* command);
+  void WhileActive(Command* command);
+  void WhenInactive(Command* command);
+  void CancelWhenActive(Command* command);
+  void ToggleWhenActive(Command* command);
+
+  void InitTable(std::shared_ptr<ITable> subtable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+  std::string GetSmartDashboardType() const override;
+
+ protected:
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/CircularBuffer.h b/wpilibc/shared/include/CircularBuffer.h
new file mode 100644
index 0000000..d273992
--- /dev/null
+++ b/wpilibc/shared/include/CircularBuffer.h
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <cstddef>
+#include <vector>
+
+namespace frc {
+
+/**
+ * This is a simple circular buffer so we don't need to "bucket brigade" copy
+ * old values.
+ */
+template <class T>
+class CircularBuffer {
+ public:
+  explicit CircularBuffer(size_t size);
+
+  void PushFront(T value);
+  void PushBack(T value);
+  T PopFront();
+  T PopBack();
+  void Resize(size_t size);
+  void Reset();
+
+  T& operator[](size_t index);
+  const T& operator[](size_t index) const;
+
+ private:
+  std::vector<T> m_data;
+
+  // Index of element at front of buffer
+  size_t m_front = 0;
+
+  // Number of elements used in buffer
+  size_t m_length = 0;
+
+  size_t ModuloInc(size_t index);
+  size_t ModuloDec(size_t index);
+};
+
+}  // namespace frc
+
+#include "CircularBuffer.inc"
diff --git a/wpilibc/shared/include/CircularBuffer.inc b/wpilibc/shared/include/CircularBuffer.inc
new file mode 100644
index 0000000..6f1e2c3
--- /dev/null
+++ b/wpilibc/shared/include/CircularBuffer.inc
@@ -0,0 +1,189 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <algorithm>
+
+namespace frc {
+
+template <class T>
+CircularBuffer<T>::CircularBuffer(size_t size) : m_data(size, 0) {}
+
+/**
+ * Push new value onto front of the buffer. The value at the back is overwritten
+ * if the buffer is full.
+ */
+template <class T>
+void CircularBuffer<T>::PushFront(T value) {
+  if (m_data.size() == 0) {
+    return;
+  }
+
+  m_front = ModuloDec(m_front);
+
+  m_data[m_front] = value;
+
+  if (m_length < m_data.size()) {
+    m_length++;
+  }
+}
+
+/**
+ * Push new value onto back of the buffer. The value at the front is overwritten
+ * if the buffer is full.
+ */
+template <class T>
+void CircularBuffer<T>::PushBack(T value) {
+  if (m_data.size() == 0) {
+    return;
+  }
+
+  m_data[(m_front + m_length) % m_data.size()] = value;
+
+  if (m_length < m_data.size()) {
+    m_length++;
+  } else {
+    // Increment front if buffer is full to maintain size
+    m_front = ModuloInc(m_front);
+  }
+}
+
+/**
+ * Pop value at front of buffer.
+ */
+template <class T>
+T CircularBuffer<T>::PopFront() {
+  // If there are no elements in the buffer, do nothing
+  if (m_length == 0) {
+    return 0;
+  }
+
+  T& temp = m_data[m_front];
+  m_front = ModuloInc(m_front);
+  m_length--;
+  return temp;
+}
+
+/**
+ * Pop value at back of buffer.
+ */
+template <class T>
+T CircularBuffer<T>::PopBack() {
+  // If there are no elements in the buffer, do nothing
+  if (m_length == 0) {
+    return 0;
+  }
+
+  m_length--;
+  return m_data[(m_front + m_length) % m_data.size()];
+}
+
+/**
+ * Resizes internal buffer to given size.
+ */
+template <class T>
+void CircularBuffer<T>::Resize(size_t size) {
+  if (size > m_data.size()) {
+    // Find end of buffer
+    size_t insertLocation = (m_front + m_length) % m_data.size();
+
+    // If insertion location precedes front of buffer, push front index back
+    if (insertLocation <= m_front) {
+      m_front += size - m_data.size();
+    }
+
+    // Add elements to end of buffer
+    m_data.insert(m_data.begin() + insertLocation, size - m_data.size(), 0);
+  } else if (size < m_data.size()) {
+    /* 1) Shift element block start at "front" left as many blocks as were
+     *    removed up to but not exceeding buffer[0]
+     * 2) Shrink buffer, which will remove even more elements automatically if
+     *    necessary
+     */
+    size_t elemsToRemove = m_data.size() - size;
+    auto frontIter = m_data.begin() + m_front;
+    if (m_front < elemsToRemove) {
+      /* Remove elements from end of buffer before shifting start of element
+       * block. Doing so saves a few copies.
+       */
+      m_data.erase(frontIter + size, m_data.end());
+
+      // Shift start of element block to left
+      m_data.erase(m_data.begin(), frontIter);
+
+      // Update metadata
+      m_front = 0;
+    } else {
+      // Shift start of element block to left
+      m_data.erase(frontIter - elemsToRemove, frontIter);
+
+      // Update metadata
+      m_front -= elemsToRemove;
+    }
+
+    /* Length only changes during a shrink if all unused spaces have been
+     * removed. Length decreases as used spaces are removed to meet the
+     * required size.
+     */
+    if (m_length > size) {
+      m_length = size;
+    }
+  }
+}
+
+/**
+ * Sets internal buffer contents to zero.
+ */
+template <class T>
+void CircularBuffer<T>::Reset() {
+  std::fill(m_data.begin(), m_data.end(), 0);
+  m_front = 0;
+  m_length = 0;
+}
+
+/**
+ * @return Element at index starting from front of buffer.
+ */
+template <class T>
+T& CircularBuffer<T>::operator[](size_t index) {
+  return m_data[(m_front + index) % m_data.size()];
+}
+
+/**
+ * @return Element at index starting from front of buffer.
+ */
+template <class T>
+const T& CircularBuffer<T>::operator[](size_t index) const {
+  return m_data[(m_front + index) % m_data.size()];
+}
+
+/**
+ * Increment an index modulo the length of the buffer.
+ *
+ * @return The result of the modulo operation.
+ */
+template <class T>
+size_t CircularBuffer<T>::ModuloInc(size_t index) {
+  return (index + 1) % m_data.size();
+}
+
+/**
+ * Decrement an index modulo the length of the buffer.
+ *
+ * @return The result of the modulo operation.
+ */
+template <class T>
+size_t CircularBuffer<T>::ModuloDec(size_t index) {
+  if (index == 0) {
+    return m_data.size() - 1;
+  } else {
+    return index - 1;
+  }
+}
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/Command.h b/wpilibc/shared/include/Commands/Command.h
new file mode 100644
index 0000000..19d1e7a
--- /dev/null
+++ b/wpilibc/shared/include/Commands/Command.h
@@ -0,0 +1,173 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <memory>
+#include <set>
+#include <string>
+
+#include "ErrorBase.h"
+#include "SmartDashboard/NamedSendable.h"
+#include "tables/ITableListener.h"
+
+namespace frc {
+
+class CommandGroup;
+class Subsystem;
+
+/**
+ * The Command class is at the very core of the entire command framework.
+ * Every command can be started with a call to {@link Command#Start() Start()}.
+ * Once a command is started it will call {@link Command#Initialize()
+ * Initialize()}, and then will repeatedly call
+ * {@link Command#Execute() Execute()} until the
+ * {@link Command#IsFinished() IsFinished()} returns true.  Once it does,
+ * {@link Command#End() End()} will be called.
+ *
+ * <p>However, if at any point while it is running {@link Command#Cancel()
+ * Cancel()} is called, then the command will be stopped and
+ * {@link Command#Interrupted() Interrupted()} will be called.</p>
+ *
+ * <p>If a command uses a {@link Subsystem}, then it should specify that it does
+ * so by calling the {@link Command#Requires(Subsystem) Requires(...)} method
+ * in its constructor. Note that a Command may have multiple requirements, and
+ * {@link Command#Requires(Subsystem) Requires(...)} should be called for each
+ * one.</p>
+ *
+ * <p>If a command is running and a new command with shared requirements is
+ * started, then one of two things will happen.  If the active command is
+ * interruptible, then {@link Command#Cancel() Cancel()} will be called and the
+ * command will be removed to make way for the new one.  If the active command
+ * is not interruptible, the other one will not even be started, and the active
+ * one will continue functioning.</p>
+ *
+ * @see CommandGroup
+ * @see Subsystem
+ */
+class Command : public ErrorBase, public NamedSendable, public ITableListener {
+  friend class CommandGroup;
+  friend class Scheduler;
+
+ public:
+  Command();
+  explicit Command(const std::string& name);
+  explicit Command(double timeout);
+  Command(const std::string& name, double timeout);
+  virtual ~Command();
+  double TimeSinceInitialized() const;
+  void Requires(Subsystem* s);
+  bool IsCanceled() const;
+  void Start();
+  bool Run();
+  void Cancel();
+  bool IsRunning() const;
+  bool IsInterruptible() const;
+  void SetInterruptible(bool interruptible);
+  bool DoesRequire(Subsystem* subsystem) const;
+  typedef std::set<Subsystem*> SubsystemSet;
+  SubsystemSet GetRequirements() const;
+  CommandGroup* GetGroup() const;
+  void SetRunWhenDisabled(bool run);
+  bool WillRunWhenDisabled() const;
+  int GetID() const;
+
+ protected:
+  void SetTimeout(double timeout);
+  bool IsTimedOut() const;
+  bool AssertUnlocked(const std::string& message);
+  void SetParent(CommandGroup* parent);
+  void ClearRequirements();
+
+  virtual void Initialize();
+  virtual void Execute();
+
+  /**
+   * Returns whether this command is finished.
+   * If it is, then the command will be removed and {@link Command#end() end()}
+   * will be called.
+   *
+   * <p>It may be useful for a team to reference the {@link Command#isTimedOut()
+   * isTimedOut()} method for time-sensitive commands.</p>
+   *
+   * <p>Returning false will result in the command never ending automatically.
+   * It may still be cancelled manually or interrupted by another command.
+   * Returning true will result in the command executing once and finishing
+   * immediately. We recommend using {@link InstantCommand} for this.</p>
+   *
+   * @return whether this command is finished.
+   * @see Command#isTimedOut() isTimedOut()
+   */
+  virtual bool IsFinished() = 0;
+
+  virtual void End();
+  virtual void Interrupted();
+
+  virtual void _Initialize();
+  virtual void _Interrupted();
+  virtual void _Execute();
+  virtual void _End();
+  virtual void _Cancel();
+
+  friend class ConditionalCommand;
+
+ private:
+  void LockChanges();
+  /*synchronized*/ void Removed();
+  void StartRunning();
+  void StartTiming();
+
+  /** The name of this command */
+  std::string m_name;
+
+  /** The time since this command was initialized */
+  double m_startTime = -1;
+
+  /** The time (in seconds) before this command "times out" (or -1 if no
+   * timeout) */
+  double m_timeout;
+
+  /** Whether or not this command has been initialized */
+  bool m_initialized = false;
+
+  /** The requirements (or null if no requirements) */
+  SubsystemSet m_requirements;
+
+  /** Whether or not it is running */
+  bool m_running = false;
+
+  /** Whether or not it is interruptible*/
+  bool m_interruptible = true;
+
+  /** Whether or not it has been canceled */
+  bool m_canceled = false;
+
+  /** Whether or not it has been locked */
+  bool m_locked = false;
+
+  /** Whether this command should run when the robot is disabled */
+  bool m_runWhenDisabled = false;
+
+  /** The {@link CommandGroup} this is in */
+  CommandGroup* m_parent = nullptr;
+
+  int m_commandID = m_commandCounter++;
+  static int m_commandCounter;
+
+ public:
+  std::string GetName() const override;
+  void InitTable(std::shared_ptr<ITable> subtable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+  std::string GetSmartDashboardType() const override;
+  void ValueChanged(ITable* source, llvm::StringRef key,
+                    std::shared_ptr<nt::Value> value, bool isNew) override;
+
+ protected:
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/CommandGroup.h b/wpilibc/shared/include/Commands/CommandGroup.h
new file mode 100644
index 0000000..a0315d5
--- /dev/null
+++ b/wpilibc/shared/include/Commands/CommandGroup.h
@@ -0,0 +1,76 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <list>
+#include <string>
+#include <vector>
+
+#include "Commands/Command.h"
+#include "Commands/CommandGroupEntry.h"
+
+namespace frc {
+
+/**
+ * A {@link CommandGroup} is a list of commands which are executed in sequence.
+ *
+ * <p>Commands in a {@link CommandGroup} are added using the {@link
+ * CommandGroup#AddSequential(Command) AddSequential(...)} method and are
+ * called sequentially. {@link CommandGroup CommandGroups} are themselves
+ * {@link Command Commands} and can be given to other
+ * {@link CommandGroup CommandGroups}.</p>
+ *
+ * <p>{@link CommandGroup CommandGroups} will carry all of the requirements of
+ * their {@link Command subcommands}.  Additional requirements can be specified
+ * by calling {@link CommandGroup#Requires(Subsystem) Requires(...)} normally
+ * in the constructor.</P>
+ *
+ * <p>CommandGroups can also execute commands in parallel, simply by adding them
+ * using {@link CommandGroup#AddParallel(Command) AddParallel(...)}.</p>
+ *
+ * @see Command
+ * @see Subsystem
+ */
+class CommandGroup : public Command {
+ public:
+  CommandGroup() = default;
+  explicit CommandGroup(const std::string& name);
+  virtual ~CommandGroup() = default;
+
+  void AddSequential(Command* command);
+  void AddSequential(Command* command, double timeout);
+  void AddParallel(Command* command);
+  void AddParallel(Command* command, double timeout);
+  bool IsInterruptible() const;
+  int GetSize() const;
+
+ protected:
+  virtual void Initialize();
+  virtual void Execute();
+  virtual bool IsFinished();
+  virtual void End();
+  virtual void Interrupted();
+  virtual void _Initialize();
+  virtual void _Interrupted();
+  virtual void _Execute();
+  virtual void _End();
+
+ private:
+  void CancelConflicts(Command* command);
+
+  /** The commands in this group (stored in entries) */
+  std::vector<CommandGroupEntry> m_commands;
+
+  /** The active children in this group (stored in entries) */
+  std::list<CommandGroupEntry> m_children;
+
+  /** The current command, -1 signifies that none have been run */
+  int m_currentCommandIndex = -1;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/CommandGroupEntry.h b/wpilibc/shared/include/Commands/CommandGroupEntry.h
new file mode 100644
index 0000000..b1f3e91
--- /dev/null
+++ b/wpilibc/shared/include/Commands/CommandGroupEntry.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* 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 Command;
+
+class CommandGroupEntry {
+ public:
+  typedef enum {
+    kSequence_InSequence,
+    kSequence_BranchPeer,
+    kSequence_BranchChild
+  } Sequence;
+
+  CommandGroupEntry() = default;
+  CommandGroupEntry(Command* command, Sequence state, double timeout = -1.0);
+  bool IsTimedOut() const;
+
+  double m_timeout = -1.0;
+  Command* m_command = nullptr;
+  Sequence m_state = kSequence_InSequence;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/ConditionalCommand.h b/wpilibc/shared/include/Commands/ConditionalCommand.h
new file mode 100644
index 0000000..e7fcb3c
--- /dev/null
+++ b/wpilibc/shared/include/Commands/ConditionalCommand.h
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2017. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include "Commands/Command.h"
+#include "Commands/InstantCommand.h"
+
+namespace frc {
+
+/**
+ * A {@link ConditionalCommand} is a {@link Command} that starts one of two
+ * commands.
+ *
+ * <p>
+ * A {@link ConditionalCommand} uses m_condition to determine whether it should
+ * run m_onTrue or m_onFalse.
+ * </p>
+ *
+ * <p>
+ * A {@link ConditionalCommand} adds the proper {@link Command} to the {@link
+ * Scheduler} during {@link ConditionalCommand#initialize()} and then {@link
+ * ConditionalCommand#isFinished()} will return true once that {@link Command}
+ * has finished executing.
+ * </p>
+ *
+ * <p>
+ * If no {@link Command} is specified for m_onFalse, the occurrence of that
+ * condition will be a no-op.
+ * </p>
+ *
+ * @see Command
+ * @see Scheduler
+ */
+class ConditionalCommand : public Command {
+ public:
+  explicit ConditionalCommand(Command* onTrue,
+                              Command* onFalse = new InstantCommand());
+  ConditionalCommand(const std::string& name, Command* onTrue,
+                     Command* onFalse = new InstantCommand());
+  virtual ~ConditionalCommand() = default;
+
+ protected:
+  /**
+   * The Condition to test to determine which Command to run.
+   *
+   * @return true if m_onTrue should be run or false if m_onFalse should be run.
+   */
+  virtual bool Condition() = 0;
+
+  void _Initialize() override;
+  void _Cancel() override;
+  bool IsFinished() override;
+  void Interrupted() override;
+
+ private:
+  /**
+   * The Command to execute if {@link ConditionalCommand#Condition()} returns
+   * true
+   */
+  Command* m_onTrue;
+
+  /**
+   * The Command to execute if {@link ConditionalCommand#Condition()} returns
+   * false
+   */
+  Command* m_onFalse;
+
+  /**
+   * Stores command chosen by condition
+   */
+  Command* m_chosenCommand = nullptr;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/InstantCommand.h b/wpilibc/shared/include/Commands/InstantCommand.h
new file mode 100644
index 0000000..1ac2bd0
--- /dev/null
+++ b/wpilibc/shared/include/Commands/InstantCommand.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
+
+#include <string>
+
+#include "Commands/Command.h"
+
+namespace frc {
+
+/**
+ * This command will execute once, then finish immediately afterward.
+ *
+ * <p>Subclassing {@link InstantCommand} is shorthand for returning true from
+ * {@link Command isFinished}.
+ */
+class InstantCommand : public Command {
+ public:
+  explicit InstantCommand(const std::string& name);
+  InstantCommand() = default;
+  virtual ~InstantCommand() = default;
+
+ protected:
+  bool IsFinished() override;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/PIDCommand.h b/wpilibc/shared/include/Commands/PIDCommand.h
new file mode 100644
index 0000000..4cc426e
--- /dev/null
+++ b/wpilibc/shared/include/Commands/PIDCommand.h
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <memory>
+#include <string>
+
+#include "Commands/Command.h"
+#include "PIDController.h"
+#include "PIDOutput.h"
+#include "PIDSource.h"
+
+namespace frc {
+
+class PIDCommand : public Command, public PIDOutput, public PIDSource {
+ public:
+  PIDCommand(const std::string& name, double p, double i, double d);
+  PIDCommand(const std::string& name, double p, double i, double d,
+             double period);
+  PIDCommand(const std::string& name, double p, double i, double d, double f,
+             double period);
+  PIDCommand(double p, double i, double d);
+  PIDCommand(double p, double i, double d, double period);
+  PIDCommand(double p, double i, double d, double f, double period);
+  virtual ~PIDCommand() = default;
+
+  void SetSetpointRelative(double deltaSetpoint);
+
+  // PIDOutput interface
+  virtual void PIDWrite(double output);
+
+  // PIDSource interface
+  virtual double PIDGet();
+
+ protected:
+  std::shared_ptr<PIDController> GetPIDController() const;
+  virtual void _Initialize();
+  virtual void _Interrupted();
+  virtual void _End();
+  void SetSetpoint(double setpoint);
+  double GetSetpoint() const;
+  double GetPosition();
+
+  virtual double ReturnPIDInput() = 0;
+  virtual void UsePIDOutput(double output) = 0;
+
+ private:
+  /** The internal {@link PIDController} */
+  std::shared_ptr<PIDController> m_controller;
+
+ public:
+  void InitTable(std::shared_ptr<ITable> subtable) override;
+  std::string GetSmartDashboardType() const override;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/PIDSubsystem.h b/wpilibc/shared/include/Commands/PIDSubsystem.h
new file mode 100644
index 0000000..d73aef6
--- /dev/null
+++ b/wpilibc/shared/include/Commands/PIDSubsystem.h
@@ -0,0 +1,76 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <memory>
+#include <string>
+
+#include "Commands/Subsystem.h"
+#include "PIDController.h"
+#include "PIDOutput.h"
+#include "PIDSource.h"
+
+namespace frc {
+
+/**
+ * This class is designed to handle the case where there is a {@link Subsystem}
+ * which uses a single {@link PIDController} almost constantly (for instance,
+ * an elevator which attempts to stay at a constant height).
+ *
+ * <p>It provides some convenience methods to run an internal {@link
+ * PIDController}. It also allows access to the internal {@link PIDController}
+ * in order to give total control to the programmer.</p>
+ *
+ */
+class PIDSubsystem : public Subsystem, public PIDOutput, public PIDSource {
+ public:
+  PIDSubsystem(const std::string& name, double p, double i, double d);
+  PIDSubsystem(const std::string& name, double p, double i, double d, double f);
+  PIDSubsystem(const std::string& name, double p, double i, double d, double f,
+               double period);
+  PIDSubsystem(double p, double i, double d);
+  PIDSubsystem(double p, double i, double d, double f);
+  PIDSubsystem(double p, double i, double d, double f, double period);
+  virtual ~PIDSubsystem() = default;
+
+  void Enable();
+  void Disable();
+
+  // PIDOutput interface
+  virtual void PIDWrite(double output);
+
+  // PIDSource interface
+  virtual double PIDGet();
+  void SetSetpoint(double setpoint);
+  void SetSetpointRelative(double deltaSetpoint);
+  void SetInputRange(double minimumInput, double maximumInput);
+  void SetOutputRange(double minimumOutput, double maximumOutput);
+  double GetSetpoint();
+  double GetPosition();
+  double GetRate();
+
+  virtual void SetAbsoluteTolerance(double absValue);
+  virtual void SetPercentTolerance(double percent);
+  virtual bool OnTarget() const;
+
+ protected:
+  std::shared_ptr<PIDController> GetPIDController();
+
+  virtual double ReturnPIDInput() = 0;
+  virtual void UsePIDOutput(double output) = 0;
+
+ private:
+  /** The internal {@link PIDController} */
+  std::shared_ptr<PIDController> m_controller;
+
+ public:
+  void InitTable(std::shared_ptr<ITable> subtable) override;
+  std::string GetSmartDashboardType() const override;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/PrintCommand.h b/wpilibc/shared/include/Commands/PrintCommand.h
new file mode 100644
index 0000000..ee8396b
--- /dev/null
+++ b/wpilibc/shared/include/Commands/PrintCommand.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <string>
+
+#include "Commands/InstantCommand.h"
+
+namespace frc {
+
+class PrintCommand : public InstantCommand {
+ public:
+  explicit PrintCommand(const std::string& message);
+  virtual ~PrintCommand() = default;
+
+ protected:
+  virtual void Initialize();
+
+ private:
+  std::string m_message;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/Scheduler.h b/wpilibc/shared/include/Commands/Scheduler.h
new file mode 100644
index 0000000..eb749aa
--- /dev/null
+++ b/wpilibc/shared/include/Commands/Scheduler.h
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <list>
+#include <map>
+#include <memory>
+#include <set>
+#include <string>
+#include <vector>
+
+#include "Commands/Command.h"
+#include "ErrorBase.h"
+#include "HAL/cpp/priority_mutex.h"
+#include "SmartDashboard/NamedSendable.h"
+#include "SmartDashboard/SmartDashboard.h"
+#include "networktables/NetworkTable.h"
+
+namespace frc {
+
+class ButtonScheduler;
+class Subsystem;
+
+class Scheduler : public ErrorBase, public NamedSendable {
+ public:
+  static Scheduler* GetInstance();
+
+  void AddCommand(Command* command);
+  void AddButton(ButtonScheduler* button);
+  void RegisterSubsystem(Subsystem* subsystem);
+  void Run();
+  void Remove(Command* command);
+  void RemoveAll();
+  void ResetAll();
+  void SetEnabled(bool enabled);
+
+  void UpdateTable();
+  std::string GetSmartDashboardType() const;
+  void InitTable(std::shared_ptr<ITable> subTable);
+  std::shared_ptr<ITable> GetTable() const;
+  std::string GetName() const;
+  std::string GetType() const;
+
+ private:
+  Scheduler();
+  virtual ~Scheduler() = default;
+
+  void ProcessCommandAddition(Command* command);
+
+  Command::SubsystemSet m_subsystems;
+  priority_mutex m_buttonsLock;
+  typedef std::vector<ButtonScheduler*> ButtonVector;
+  ButtonVector m_buttons;
+  typedef std::vector<Command*> CommandVector;
+  priority_mutex m_additionsLock;
+  CommandVector m_additions;
+  typedef std::set<Command*> CommandSet;
+  CommandSet m_commands;
+  bool m_adding = false;
+  bool m_enabled = true;
+  std::vector<std::string> commands;
+  std::vector<double> ids;
+  std::vector<double> toCancel;
+  std::shared_ptr<ITable> m_table;
+  bool m_runningCommandsChanged = false;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/StartCommand.h b/wpilibc/shared/include/Commands/StartCommand.h
new file mode 100644
index 0000000..9ac4d21
--- /dev/null
+++ b/wpilibc/shared/include/Commands/StartCommand.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Commands/InstantCommand.h"
+
+namespace frc {
+
+class StartCommand : public InstantCommand {
+ public:
+  explicit StartCommand(Command* commandToStart);
+  virtual ~StartCommand() = default;
+
+ protected:
+  virtual void Initialize();
+
+ private:
+  Command* m_commandToFork;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/Subsystem.h b/wpilibc/shared/include/Commands/Subsystem.h
new file mode 100644
index 0000000..3121098
--- /dev/null
+++ b/wpilibc/shared/include/Commands/Subsystem.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <memory>
+#include <string>
+
+#include "ErrorBase.h"
+#include "SmartDashboard/NamedSendable.h"
+
+namespace frc {
+
+class Command;
+
+class Subsystem : public ErrorBase, public NamedSendable {
+  friend class Scheduler;
+
+ public:
+  explicit Subsystem(const std::string& name);
+  virtual ~Subsystem() = default;
+
+  void SetDefaultCommand(Command* command);
+  Command* GetDefaultCommand();
+  void SetCurrentCommand(Command* command);
+  Command* GetCurrentCommand() const;
+  virtual void InitDefaultCommand();
+
+ private:
+  void ConfirmCommand();
+
+  Command* m_currentCommand = nullptr;
+  bool m_currentCommandChanged = true;
+  Command* m_defaultCommand = nullptr;
+  std::string m_name;
+  bool m_initializedDefaultCommand = false;
+
+ public:
+  std::string GetName() const override;
+  void InitTable(std::shared_ptr<ITable> subtable) override;
+  std::shared_ptr<ITable> GetTable() const override;
+  std::string GetSmartDashboardType() const override;
+
+ protected:
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/TimedCommand.h b/wpilibc/shared/include/Commands/TimedCommand.h
new file mode 100644
index 0000000..3331aa3
--- /dev/null
+++ b/wpilibc/shared/include/Commands/TimedCommand.h
@@ -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 "Commands/Command.h"
+
+namespace frc {
+
+/**
+ * A {@link TimedCommand} will wait for a timeout before finishing.
+ * {@link TimedCommand} is used to execute a command for a given amount of time.
+ */
+class TimedCommand : public Command {
+ public:
+  TimedCommand(const std::string& name, double timeout);
+  explicit TimedCommand(double timeout);
+  virtual ~TimedCommand() = default;
+
+ protected:
+  bool IsFinished() override;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/WaitCommand.h b/wpilibc/shared/include/Commands/WaitCommand.h
new file mode 100644
index 0000000..e1be8aa
--- /dev/null
+++ b/wpilibc/shared/include/Commands/WaitCommand.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <string>
+
+#include "Commands/TimedCommand.h"
+
+namespace frc {
+
+class WaitCommand : public TimedCommand {
+ public:
+  explicit WaitCommand(double timeout);
+  WaitCommand(const std::string& name, double timeout);
+  virtual ~WaitCommand() = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/WaitForChildren.h b/wpilibc/shared/include/Commands/WaitForChildren.h
new file mode 100644
index 0000000..3537805
--- /dev/null
+++ b/wpilibc/shared/include/Commands/WaitForChildren.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <string>
+
+#include "Commands/Command.h"
+
+namespace frc {
+
+class WaitForChildren : public Command {
+ public:
+  explicit WaitForChildren(double timeout);
+  WaitForChildren(const std::string& name, double timeout);
+  virtual ~WaitForChildren() = default;
+
+ protected:
+  virtual bool IsFinished();
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Commands/WaitUntilCommand.h b/wpilibc/shared/include/Commands/WaitUntilCommand.h
new file mode 100644
index 0000000..190522d
--- /dev/null
+++ b/wpilibc/shared/include/Commands/WaitUntilCommand.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <string>
+
+#include "Commands/Command.h"
+
+namespace frc {
+
+class WaitUntilCommand : public Command {
+ public:
+  explicit WaitUntilCommand(double time);
+  WaitUntilCommand(const std::string& name, double time);
+  virtual ~WaitUntilCommand() = default;
+
+ protected:
+  virtual bool IsFinished();
+
+ private:
+  double m_time;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Controller.h b/wpilibc/shared/include/Controller.h
new file mode 100644
index 0000000..68c2712
--- /dev/null
+++ b/wpilibc/shared/include/Controller.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
+
+namespace frc {
+
+/**
+ * Interface for Controllers.
+ * Common interface for controllers. Controllers run control loops, the most
+ * common are PID controllers and their variants, but this includes anything
+ * that is controlling an actuator in a separate thread.
+ */
+class Controller {
+ public:
+  virtual ~Controller() = default;
+
+  /**
+   * Allows the control loop to run
+   */
+  virtual void Enable() = 0;
+
+  /**
+   * Stops the control loop from running until explicitly re-enabled by calling
+   * enable()
+   */
+  virtual void Disable() = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Error.h b/wpilibc/shared/include/Error.h
new file mode 100644
index 0000000..435c644
--- /dev/null
+++ b/wpilibc/shared/include/Error.h
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <string>
+
+#include "Base.h"
+#include "llvm/StringRef.h"
+
+#ifdef _WIN32
+#include <Windows.h>
+// Windows.h defines #define GetMessage GetMessageW, which we don't want.
+#undef GetMessage
+#endif
+
+namespace frc {
+
+//  Forward declarations
+class ErrorBase;
+
+/**
+ * Error object represents a library error.
+ */
+class Error {
+ public:
+  typedef int Code;
+
+  Error() = default;
+
+  Error(const Error&) = delete;
+  Error& operator=(const Error&) = delete;
+
+  void Clone(const Error& error);
+  Code GetCode() const;
+  std::string GetMessage() const;
+  std::string GetFilename() const;
+  std::string GetFunction() const;
+  int GetLineNumber() const;
+  const ErrorBase* GetOriginatingObject() const;
+  double GetTimestamp() const;
+  void Clear();
+  void Set(Code code, llvm::StringRef contextMessage, llvm::StringRef filename,
+           llvm::StringRef function, int lineNumber,
+           const ErrorBase* originatingObject);
+
+ private:
+  void Report();
+
+  Code m_code = 0;
+  std::string m_message;
+  std::string m_filename;
+  std::string m_function;
+  int m_lineNumber = 0;
+  const ErrorBase* m_originatingObject = nullptr;
+  double m_timestamp = 0.0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/ErrorBase.h b/wpilibc/shared/include/ErrorBase.h
new file mode 100644
index 0000000..652e8ea
--- /dev/null
+++ b/wpilibc/shared/include/ErrorBase.h
@@ -0,0 +1,120 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Base.h"
+#include "Error.h"
+#include "HAL/cpp/priority_mutex.h"
+#include "llvm/StringRef.h"
+
+#define wpi_setErrnoErrorWithContext(context) \
+  this->SetErrnoError((context), __FILE__, __FUNCTION__, __LINE__)
+#define wpi_setErrnoError() wpi_setErrnoErrorWithContext("")
+#define wpi_setImaqErrorWithContext(code, context)                             \
+  do {                                                                         \
+    if ((code) != 0)                                                           \
+      this->SetImaqError((code), (context), __FILE__, __FUNCTION__, __LINE__); \
+  } while (0)
+#define wpi_setErrorWithContext(code, context)                             \
+  do {                                                                     \
+    if ((code) != 0)                                                       \
+      this->SetError((code), (context), __FILE__, __FUNCTION__, __LINE__); \
+  } while (0)
+#define wpi_setErrorWithContextRange(code, min, max, req, context)          \
+  do {                                                                      \
+    if ((code) != 0)                                                        \
+      this->SetErrorRange((code), (min), (max), (req), (context), __FILE__, \
+                          __FUNCTION__, __LINE__);                          \
+  } while (0)
+#define wpi_setError(code) wpi_setErrorWithContext(code, "")
+#define wpi_setStaticErrorWithContext(object, code, context)                 \
+  do {                                                                       \
+    if ((code) != 0)                                                         \
+      object->SetError((code), (context), __FILE__, __FUNCTION__, __LINE__); \
+  } while (0)
+#define wpi_setStaticError(object, code) \
+  wpi_setStaticErrorWithContext(object, code, "")
+#define wpi_setGlobalErrorWithContext(code, context)                \
+  do {                                                              \
+    if ((code) != 0)                                                \
+      ::frc::ErrorBase::SetGlobalError((code), (context), __FILE__, \
+                                       __FUNCTION__, __LINE__);     \
+  } while (0)
+#define wpi_setGlobalError(code) wpi_setGlobalErrorWithContext(code, "")
+#define wpi_setWPIErrorWithContext(error, context)                    \
+  this->SetWPIError((wpi_error_s_##error), (wpi_error_value_##error), \
+                    (context), __FILE__, __FUNCTION__, __LINE__)
+#define wpi_setWPIError(error) (wpi_setWPIErrorWithContext(error, ""))
+#define wpi_setStaticWPIErrorWithContext(object, error, context)  \
+  object->SetWPIError((wpi_error_s_##error), (context), __FILE__, \
+                      __FUNCTION__, __LINE__)
+#define wpi_setStaticWPIError(object, error) \
+  wpi_setStaticWPIErrorWithContext(object, error, "")
+#define wpi_setGlobalWPIErrorWithContext(error, context)                \
+  ::frc::ErrorBase::SetGlobalWPIError((wpi_error_s_##error), (context), \
+                                      __FILE__, __FUNCTION__, __LINE__)
+#define wpi_setGlobalWPIError(error) wpi_setGlobalWPIErrorWithContext(error, "")
+
+namespace frc {
+
+/**
+ * Base class for most objects.
+ * ErrorBase is the base class for most objects since it holds the generated
+ * error
+ * for that object. In addition, there is a single instance of a global error
+ * object
+ */
+class ErrorBase {
+  // TODO: Consider initializing instance variables and cleanup in destructor
+ public:
+  ErrorBase() = default;
+  virtual ~ErrorBase() = default;
+
+  ErrorBase(const ErrorBase&) = delete;
+  ErrorBase& operator=(const ErrorBase&) = delete;
+
+  virtual Error& GetError();
+  virtual const Error& GetError() const;
+  virtual void SetErrnoError(llvm::StringRef contextMessage,
+                             llvm::StringRef filename, llvm::StringRef function,
+                             int lineNumber) const;
+  virtual void SetImaqError(int success, llvm::StringRef contextMessage,
+                            llvm::StringRef filename, llvm::StringRef function,
+                            int lineNumber) const;
+  virtual void SetError(Error::Code code, llvm::StringRef contextMessage,
+                        llvm::StringRef filename, llvm::StringRef function,
+                        int lineNumber) const;
+  virtual void SetErrorRange(Error::Code code, int32_t minRange,
+                             int32_t maxRange, int32_t requestedValue,
+                             llvm::StringRef contextMessage,
+                             llvm::StringRef filename, llvm::StringRef function,
+                             int lineNumber) const;
+  virtual void SetWPIError(llvm::StringRef errorMessage, Error::Code code,
+                           llvm::StringRef contextMessage,
+                           llvm::StringRef filename, llvm::StringRef function,
+                           int lineNumber) const;
+  virtual void CloneError(const ErrorBase& rhs) const;
+  virtual void ClearError() const;
+  virtual bool StatusIsFatal() const;
+  static void SetGlobalError(Error::Code code, llvm::StringRef contextMessage,
+                             llvm::StringRef filename, llvm::StringRef function,
+                             int lineNumber);
+  static void SetGlobalWPIError(llvm::StringRef errorMessage,
+                                llvm::StringRef contextMessage,
+                                llvm::StringRef filename,
+                                llvm::StringRef function, int lineNumber);
+  static Error& GetGlobalError();
+
+ protected:
+  mutable Error m_error;
+  // TODO: Replace globalError with a global list of all errors.
+  static priority_mutex _globalErrorMutex;
+  static Error _globalError;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Filters/Filter.h b/wpilibc/shared/include/Filters/Filter.h
new file mode 100644
index 0000000..eabc1c7
--- /dev/null
+++ b/wpilibc/shared/include/Filters/Filter.h
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "PIDSource.h"
+
+namespace frc {
+
+/**
+ * Interface for filters
+ */
+class Filter : public PIDSource {
+ public:
+  explicit Filter(std::shared_ptr<PIDSource> source);
+  virtual ~Filter() = default;
+
+  // PIDSource interface
+  void SetPIDSourceType(PIDSourceType pidSource) override;
+  PIDSourceType GetPIDSourceType() const;
+  double PIDGet() override = 0;
+
+  /**
+   * Returns the current filter estimate without also inserting new data as
+   * PIDGet() would do.
+   *
+   * @return The current filter estimate
+   */
+  virtual double Get() const = 0;
+
+  /**
+   * Reset the filter state
+   */
+  virtual void Reset() = 0;
+
+ protected:
+  /**
+   * Calls PIDGet() of source
+   *
+   * @return Current value of source
+   */
+  double PIDGetSource();
+
+ private:
+  std::shared_ptr<PIDSource> m_source;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Filters/LinearDigitalFilter.h b/wpilibc/shared/include/Filters/LinearDigitalFilter.h
new file mode 100644
index 0000000..a9fabc4
--- /dev/null
+++ b/wpilibc/shared/include/Filters/LinearDigitalFilter.h
@@ -0,0 +1,106 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <initializer_list>
+#include <memory>
+#include <vector>
+
+#include "CircularBuffer.h"
+#include "Filter.h"
+
+namespace frc {
+
+/**
+ * This class implements a linear, digital filter. All types of FIR and IIR
+ * filters are supported. Static factory methods are provided to create commonly
+ * used types of filters.
+ *
+ * Filters are of the form:<br>
+ *  y[n] = (b0 * x[n] + b1 * x[n-1] + … + bP * x[n-P]) -
+ *         (a0 * y[n-1] + a2 * y[n-2] + … + aQ * y[n-Q])
+ *
+ * Where:<br>
+ *  y[n] is the output at time "n"<br>
+ *  x[n] is the input at time "n"<br>
+ *  y[n-1] is the output from the LAST time step ("n-1")<br>
+ *  x[n-1] is the input from the LAST time step ("n-1")<br>
+ *  b0 … bP are the "feedforward" (FIR) gains<br>
+ *  a0 … aQ are the "feedback" (IIR) gains<br>
+ * IMPORTANT! Note the "-" sign in front of the feedback term! This is a common
+ *            convention in signal processing.
+ *
+ * What can linear filters do? Basically, they can filter, or diminish, the
+ * effects of undesirable input frequencies. High frequencies, or rapid changes,
+ * can be indicative of sensor noise or be otherwise undesirable. A "low pass"
+ * filter smooths out the signal, reducing the impact of these high frequency
+ * components.  Likewise, a "high pass" filter gets rid of slow-moving signal
+ * components, letting you detect large changes more easily.
+ *
+ * Example FRC applications of filters:
+ *  - Getting rid of noise from an analog sensor input (note: the roboRIO's FPGA
+ *    can do this faster in hardware)
+ *  - Smoothing out joystick input to prevent the wheels from slipping or the
+ *    robot from tipping
+ *  - Smoothing motor commands so that unnecessary strain isn't put on
+ *    electrical or mechanical components
+ *  - If you use clever gains, you can make a PID controller out of this class!
+ *
+ * For more on filters, I highly recommend the following articles:<br>
+ *  http://en.wikipedia.org/wiki/Linear_filter<br>
+ *  http://en.wikipedia.org/wiki/Iir_filter<br>
+ *  http://en.wikipedia.org/wiki/Fir_filter<br>
+ *
+ * Note 1: PIDGet() should be called by the user on a known, regular period.
+ * You can set up a Notifier to do this (look at the WPILib PIDController
+ * class), or do it "inline" with code in a periodic function.
+ *
+ * Note 2: For ALL filters, gains are necessarily a function of frequency. If
+ * you make a filter that works well for you at, say, 100Hz, you will most
+ * definitely need to adjust the gains if you then want to run it at 200Hz!
+ * Combining this with Note 1 - the impetus is on YOU as a developer to make
+ * sure PIDGet() gets called at the desired, constant frequency!
+ */
+class LinearDigitalFilter : public Filter {
+ public:
+  LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                      std::initializer_list<double> ffGains,
+                      std::initializer_list<double> fbGains);
+  LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                      std::initializer_list<double> ffGains,
+                      const std::vector<double>& fbGains);
+  LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                      const std::vector<double>& ffGains,
+                      std::initializer_list<double> fbGains);
+  LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                      const std::vector<double>& ffGains,
+                      const std::vector<double>& fbGains);
+
+  // Static methods to create commonly used filters
+  static LinearDigitalFilter SinglePoleIIR(std::shared_ptr<PIDSource> source,
+                                           double timeConstant, double period);
+  static LinearDigitalFilter HighPass(std::shared_ptr<PIDSource> source,
+                                      double timeConstant, double period);
+  static LinearDigitalFilter MovingAverage(std::shared_ptr<PIDSource> source,
+                                           int taps);
+
+  // Filter interface
+  double Get() const override;
+  void Reset() override;
+
+  // PIDSource interface
+  double PIDGet() override;
+
+ private:
+  CircularBuffer<double> m_inputs;
+  CircularBuffer<double> m_outputs;
+  std::vector<double> m_inputGains;
+  std::vector<double> m_outputGains;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/GamepadBase.h b/wpilibc/shared/include/GamepadBase.h
new file mode 100644
index 0000000..b073c2c
--- /dev/null
+++ b/wpilibc/shared/include/GamepadBase.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "GenericHID.h"
+
+namespace frc {
+
+/**
+ * Gamepad Interface.
+ */
+class GamepadBase : public GenericHID {
+ public:
+  explicit GamepadBase(int port);
+  virtual ~GamepadBase() = default;
+
+  virtual bool GetBumper(JoystickHand hand = kRightHand) const = 0;
+  virtual bool GetStickButton(JoystickHand hand) const = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/GenericHID.h b/wpilibc/shared/include/GenericHID.h
new file mode 100644
index 0000000..657abe6
--- /dev/null
+++ b/wpilibc/shared/include/GenericHID.h
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <string>
+
+namespace frc {
+
+class DriverStation;
+
+/**
+ * GenericHID Interface.
+ */
+class GenericHID {
+ public:
+  typedef enum { kLeftRumble, kRightRumble } RumbleType;
+
+  typedef enum {
+    kUnknown = -1,
+    kXInputUnknown = 0,
+    kXInputGamepad = 1,
+    kXInputWheel = 2,
+    kXInputArcadeStick = 3,
+    kXInputFlightStick = 4,
+    kXInputDancePad = 5,
+    kXInputGuitar = 6,
+    kXInputGuitar2 = 7,
+    kXInputDrumKit = 8,
+    kXInputGuitar3 = 11,
+    kXInputArcadePad = 19,
+    kHIDJoystick = 20,
+    kHIDGamepad = 21,
+    kHIDDriving = 22,
+    kHIDFlight = 23,
+    kHID1stPerson = 24
+  } HIDType;
+
+  enum JoystickHand { kLeftHand = 0, kRightHand = 1 };
+
+  explicit GenericHID(int port);
+  virtual ~GenericHID() = default;
+
+  virtual double GetX(JoystickHand hand = kRightHand) const = 0;
+  virtual double GetY(JoystickHand hand = kRightHand) const = 0;
+  virtual double GetRawAxis(int axis) const;
+
+  bool GetRawButton(int button) const;
+
+  int GetPOV(int pov = 0) const;
+  int GetPOVCount() const;
+
+  int GetPort() const;
+  GenericHID::HIDType GetType() const;
+  std::string GetName() const;
+
+  void SetOutput(int outputNumber, bool value);
+  void SetOutputs(int value);
+  void SetRumble(RumbleType type, double value);
+
+ private:
+  DriverStation& m_ds;
+  int m_port;
+  int m_outputs = 0;
+  uint16_t m_leftRumble = 0;
+  uint16_t m_rightRumble = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/GyroBase.h b/wpilibc/shared/include/GyroBase.h
new file mode 100644
index 0000000..03b4617
--- /dev/null
+++ b/wpilibc/shared/include/GyroBase.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 <string>
+
+#include "LiveWindow/LiveWindowSendable.h"
+#include "PIDSource.h"
+#include "SensorBase.h"
+#include "interfaces/Gyro.h"
+
+namespace frc {
+
+/**
+ * GyroBase is the common base class for Gyro implementations such as
+ * AnalogGyro.
+ */
+class GyroBase : public Gyro,
+                 public SensorBase,
+                 public PIDSource,
+                 public LiveWindowSendable {
+ public:
+  virtual ~GyroBase() = default;
+
+  // PIDSource interface
+  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:
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/HLUsageReporting.h b/wpilibc/shared/include/HLUsageReporting.h
new file mode 100644
index 0000000..3d3c47b
--- /dev/null
+++ b/wpilibc/shared/include/HLUsageReporting.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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 {
+
+class HLUsageReportingInterface {
+ public:
+  virtual ~HLUsageReportingInterface() = default;
+  virtual void ReportScheduler() = 0;
+  virtual void ReportSmartDashboard() = 0;
+};
+
+class HLUsageReporting {
+ private:
+  static HLUsageReportingInterface* impl;
+
+ public:
+  static void SetImplementation(HLUsageReportingInterface* i);
+  static void ReportScheduler();
+  static void ReportSmartDashboard();
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Joystick.h b/wpilibc/shared/include/Joystick.h
new file mode 100644
index 0000000..e4ee16f
--- /dev/null
+++ b/wpilibc/shared/include/Joystick.h
@@ -0,0 +1,88 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <vector>
+
+#include "ErrorBase.h"
+#include "JoystickBase.h"
+
+namespace frc {
+
+class DriverStation;
+
+/**
+ * Handle input from standard Joysticks connected to the Driver Station.
+ * This class handles standard input that comes from the Driver Station. Each
+ * time a value is requested the most recent value is returned. There is a
+ * single class instance for each joystick and the mapping of ports to hardware
+ * buttons depends on the code in the Driver Station.
+ */
+class Joystick : public JoystickBase, public ErrorBase {
+ public:
+  static const int kDefaultXAxis = 0;
+  static const int kDefaultYAxis = 1;
+  static const int kDefaultZAxis = 2;
+  static const int kDefaultTwistAxis = 2;
+  static const int kDefaultThrottleAxis = 3;
+
+  typedef enum {
+    kXAxis,
+    kYAxis,
+    kZAxis,
+    kTwistAxis,
+    kThrottleAxis,
+    kNumAxisTypes
+  } AxisType;
+
+  static const int kDefaultTriggerButton = 1;
+  static const int kDefaultTopButton = 2;
+
+  typedef enum { kTriggerButton, kTopButton, kNumButtonTypes } ButtonType;
+
+  explicit Joystick(int port);
+  Joystick(int port, int numAxisTypes, int numButtonTypes);
+  virtual ~Joystick() = default;
+
+  Joystick(const Joystick&) = delete;
+  Joystick& operator=(const Joystick&) = delete;
+
+  int GetAxisChannel(AxisType axis) const;
+  void SetAxisChannel(AxisType axis, int channel);
+
+  double GetX(JoystickHand hand = kRightHand) const override;
+  double GetY(JoystickHand hand = kRightHand) const override;
+  double GetZ(JoystickHand hand = kRightHand) const override;
+  double GetTwist() const override;
+  double GetThrottle() const override;
+  virtual double GetAxis(AxisType axis) const;
+
+  bool GetTrigger(JoystickHand hand = kRightHand) const override;
+  bool GetTop(JoystickHand hand = kRightHand) const override;
+  bool GetButton(ButtonType button) const;
+  static Joystick* GetStickForPort(int port);
+
+  virtual double GetMagnitude() const;
+  virtual double GetDirectionRadians() const;
+  virtual double GetDirectionDegrees() const;
+
+  int GetAxisType(int axis) const;
+
+  int GetAxisCount() const;
+  int GetButtonCount() const;
+
+ private:
+  DriverStation& m_ds;
+  std::vector<int> m_axes;
+  std::vector<int> m_buttons;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/JoystickBase.h b/wpilibc/shared/include/JoystickBase.h
new file mode 100644
index 0000000..262c3e2
--- /dev/null
+++ b/wpilibc/shared/include/JoystickBase.h
@@ -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 "GenericHID.h"
+
+namespace frc {
+
+/**
+ * Joystick Interface.
+ */
+class JoystickBase : public GenericHID {
+ public:
+  explicit JoystickBase(int port);
+  virtual ~JoystickBase() = default;
+
+  virtual double GetZ(JoystickHand hand = kRightHand) const = 0;
+  virtual double GetTwist() const = 0;
+  virtual double GetThrottle() const = 0;
+
+  virtual bool GetTrigger(JoystickHand hand = kRightHand) const = 0;
+  virtual bool GetTop(JoystickHand hand = kRightHand) const = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/LiveWindow/LiveWindow.h b/wpilibc/shared/include/LiveWindow/LiveWindow.h
new file mode 100644
index 0000000..c2be96a
--- /dev/null
+++ b/wpilibc/shared/include/LiveWindow/LiveWindow.h
@@ -0,0 +1,87 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2012-2017. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared 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 "Commands/Scheduler.h"
+#include "LiveWindow/LiveWindowSendable.h"
+#include "tables/ITable.h"
+
+namespace frc {
+
+struct LiveWindowComponent {
+  std::string subsystem;
+  std::string name;
+  bool isSensor = false;
+
+  LiveWindowComponent() = default;
+  LiveWindowComponent(std::string subsystem, std::string name, bool isSensor) {
+    this->subsystem = subsystem;
+    this->name = name;
+    this->isSensor = isSensor;
+  }
+};
+
+/**
+ * The LiveWindow class is the public interface for putting sensors and
+ * actuators
+ * on the LiveWindow.
+ */
+class LiveWindow {
+ public:
+  static LiveWindow* GetInstance();
+  void Run();
+  void AddSensor(const std::string& subsystem, const std::string& name,
+                 LiveWindowSendable* component);
+  void AddSensor(const std::string& subsystem, const std::string& name,
+                 LiveWindowSendable& component);
+  void AddSensor(const std::string& subsystem, const std::string& name,
+                 std::shared_ptr<LiveWindowSendable> component);
+  void AddActuator(const std::string& subsystem, const std::string& name,
+                   LiveWindowSendable* component);
+  void AddActuator(const std::string& subsystem, const std::string& name,
+                   LiveWindowSendable& component);
+  void AddActuator(const std::string& subsystem, const std::string& name,
+                   std::shared_ptr<LiveWindowSendable> component);
+
+  void AddSensor(std::string type, int channel, LiveWindowSendable* component);
+  void AddActuator(std::string type, int channel,
+                   LiveWindowSendable* component);
+  void AddActuator(std::string type, int module, int channel,
+                   LiveWindowSendable* component);
+
+  bool IsEnabled() const { return m_enabled; }
+  void SetEnabled(bool enabled);
+
+ protected:
+  LiveWindow();
+  virtual ~LiveWindow() = default;
+
+ private:
+  void UpdateValues();
+  void Initialize();
+  void InitializeLiveWindowComponents();
+
+  std::vector<std::shared_ptr<LiveWindowSendable>> m_sensors;
+  std::map<std::shared_ptr<LiveWindowSendable>, LiveWindowComponent>
+      m_components;
+
+  std::shared_ptr<ITable> m_liveWindowTable;
+  std::shared_ptr<ITable> m_statusTable;
+
+  Scheduler* m_scheduler;
+
+  bool m_enabled = false;
+  bool m_firstTime = true;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/LiveWindow/LiveWindowSendable.h b/wpilibc/shared/include/LiveWindow/LiveWindowSendable.h
new file mode 100644
index 0000000..08b330d
--- /dev/null
+++ b/wpilibc/shared/include/LiveWindow/LiveWindowSendable.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2012-2017. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "SmartDashboard/Sendable.h"
+
+namespace frc {
+
+/**
+ * Live Window Sendable is a special type of object sendable to the live window.
+ */
+class LiveWindowSendable : public Sendable {
+ public:
+  /**
+   * Update the table for this sendable object with the latest
+   * values.
+   */
+  virtual void UpdateTable() = 0;
+
+  /**
+   * Start having this sendable object automatically respond to
+   * value changes reflect the value on the table.
+   */
+  virtual void StartLiveWindowMode() = 0;
+
+  /**
+   * Stop having this sendable object automatically respond to value
+   * changes.
+   */
+  virtual void StopLiveWindowMode() = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/LiveWindow/LiveWindowStatusListener.h b/wpilibc/shared/include/LiveWindow/LiveWindowStatusListener.h
new file mode 100644
index 0000000..ec6fc2f
--- /dev/null
+++ b/wpilibc/shared/include/LiveWindow/LiveWindowStatusListener.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2012-2017. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared 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 "tables/ITable.h"
+#include "tables/ITableListener.h"
+
+namespace frc {
+
+class LiveWindowStatusListener : public ITableListener {
+ public:
+  virtual void ValueChanged(ITable* source, llvm::StringRef key,
+                            std::shared_ptr<nt::Value> value, bool isNew);
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/PIDController.h b/wpilibc/shared/include/PIDController.h
new file mode 100644
index 0000000..a304f9c
--- /dev/null
+++ b/wpilibc/shared/include/PIDController.h
@@ -0,0 +1,153 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <queue>
+#include <string>
+
+#include "Base.h"
+#include "Controller.h"
+#include "HAL/cpp/priority_mutex.h"
+#include "LiveWindow/LiveWindow.h"
+#include "Notifier.h"
+#include "PIDInterface.h"
+#include "PIDSource.h"
+#include "Timer.h"
+
+namespace frc {
+
+class PIDOutput;
+
+/**
+ * Class implements a PID Control Loop.
+ *
+ * Creates a separate thread which reads the given PIDSource and takes
+ * care of the integral calculations, as well as writing the given PIDOutput.
+ *
+ * This feedback controller runs in discrete time, so time deltas are not used
+ * in the integral and derivative calculations. Therefore, the sample rate
+ * affects the controller's behavior for a given set of PID constants.
+ */
+class PIDController : public LiveWindowSendable,
+                      public PIDInterface,
+                      public ITableListener {
+ public:
+  PIDController(double p, double i, double d, PIDSource* source,
+                PIDOutput* output, double period = 0.05);
+  PIDController(double p, double i, double d, double f, PIDSource* source,
+                PIDOutput* output, double period = 0.05);
+  virtual ~PIDController();
+
+  PIDController(const PIDController&) = delete;
+  PIDController& operator=(const PIDController) = delete;
+
+  virtual double Get() const;
+  virtual void SetContinuous(bool continuous = true);
+  virtual void SetInputRange(double minimumInput, double maximumInput);
+  virtual void SetOutputRange(double minimumOutput, double maximumOutput);
+  void SetPID(double p, double i, double d) override;
+  virtual void SetPID(double p, double i, double d, double f);
+  double GetP() const override;
+  double GetI() const override;
+  double GetD() const override;
+  virtual double GetF() const;
+
+  void SetSetpoint(double setpoint) override;
+  double GetSetpoint() const override;
+  double GetDeltaSetpoint() const;
+
+  virtual double GetError() const;
+  virtual double GetAvgError() const;
+
+  virtual void SetPIDSourceType(PIDSourceType pidSource);
+  virtual PIDSourceType GetPIDSourceType() const;
+
+  virtual void SetTolerance(double percent);
+  virtual void SetAbsoluteTolerance(double absValue);
+  virtual void SetPercentTolerance(double percentValue);
+  virtual void SetToleranceBuffer(int buf = 1);
+  virtual bool OnTarget() const;
+
+  void Enable() override;
+  void Disable() override;
+  bool IsEnabled() const override;
+
+  void Reset() override;
+
+  void InitTable(std::shared_ptr<ITable> subtable) override;
+
+ protected:
+  PIDSource* m_pidInput;
+  PIDOutput* m_pidOutput;
+
+  std::shared_ptr<ITable> m_table;
+  virtual void Calculate();
+  virtual double CalculateFeedForward();
+  double GetContinuousError(double error) const;
+
+ private:
+  // factor for "proportional" control
+  double m_P;
+  // factor for "integral" control
+  double m_I;
+  // factor for "derivative" control
+  double m_D;
+  // factor for "feed forward" control
+  double m_F;
+  // |maximum output|
+  double m_maximumOutput = 1.0;
+  // |minimum output|
+  double m_minimumOutput = -1.0;
+  // maximum input - limit setpoint to this
+  double m_maximumInput = 0;
+  // minimum input - limit setpoint to this
+  double m_minimumInput = 0;
+  // do the endpoints wrap around? eg. Absolute encoder
+  bool m_continuous = false;
+  // is the pid controller enabled
+  bool m_enabled = false;
+  // the prior error (used to compute velocity)
+  double m_prevError = 0;
+  // the sum of the errors for use in the integral calc
+  double m_totalError = 0;
+  enum {
+    kAbsoluteTolerance,
+    kPercentTolerance,
+    kNoTolerance
+  } m_toleranceType = kNoTolerance;
+
+  // the percetage or absolute error that is considered on target.
+  double m_tolerance = 0.05;
+  double m_setpoint = 0;
+  double m_prevSetpoint = 0;
+  double m_error = 0;
+  double m_result = 0;
+  double m_period;
+
+  // Length of buffer for averaging for tolerances.
+  std::atomic<unsigned> m_bufLength{1};
+  std::queue<double> m_buf;
+  double m_bufTotal = 0;
+
+  mutable priority_recursive_mutex m_mutex;
+
+  std::unique_ptr<Notifier> m_controlLoop;
+  Timer m_setpointTimer;
+
+  std::shared_ptr<ITable> GetTable() const override;
+  std::string GetSmartDashboardType() 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;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/PIDInterface.h b/wpilibc/shared/include/PIDInterface.h
new file mode 100644
index 0000000..608b8d8
--- /dev/null
+++ b/wpilibc/shared/include/PIDInterface.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
+
+#include "Base.h"
+#include "Controller.h"
+#include "LiveWindow/LiveWindow.h"
+
+namespace frc {
+
+class PIDInterface : public Controller {
+  virtual void SetPID(double p, double i, double d) = 0;
+  virtual double GetP() const = 0;
+  virtual double GetI() const = 0;
+  virtual double GetD() const = 0;
+
+  virtual void SetSetpoint(double setpoint) = 0;
+  virtual double GetSetpoint() const = 0;
+
+  virtual void Enable() = 0;
+  virtual void Disable() = 0;
+  virtual bool IsEnabled() const = 0;
+
+  virtual void Reset() = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/PIDOutput.h b/wpilibc/shared/include/PIDOutput.h
new file mode 100644
index 0000000..efa4255
--- /dev/null
+++ b/wpilibc/shared/include/PIDOutput.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Base.h"
+
+namespace frc {
+
+/**
+ * PIDOutput interface is a generic output for the PID class.
+ * PWMs use this class.
+ * Users implement this interface to allow for a PIDController to
+ * read directly from the inputs.
+ */
+class PIDOutput {
+ public:
+  virtual void PIDWrite(double output) = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/PIDSource.h b/wpilibc/shared/include/PIDSource.h
new file mode 100644
index 0000000..1f849c1
--- /dev/null
+++ b/wpilibc/shared/include/PIDSource.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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 PIDSourceType { kDisplacement, kRate };
+
+/**
+ * PIDSource interface is a generic sensor source for the PID class.
+ * All sensors that can be used with the PID class will implement the PIDSource
+ * that returns a standard value that will be used in the PID code.
+ */
+class PIDSource {
+ public:
+  virtual void SetPIDSourceType(PIDSourceType pidSource);
+  PIDSourceType GetPIDSourceType() const;
+  virtual double PIDGet() = 0;
+
+ protected:
+  PIDSourceType m_pidSource = PIDSourceType::kDisplacement;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Resource.h b/wpilibc/shared/include/Resource.h
new file mode 100644
index 0000000..d42ce50
--- /dev/null
+++ b/wpilibc/shared/include/Resource.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 <memory>
+#include <string>
+#include <vector>
+
+#include "ErrorBase.h"
+#include "HAL/cpp/priority_mutex.h"
+
+namespace frc {
+
+/**
+ * The Resource class is a convenient way to track allocated resources.
+ * It tracks them as indicies in the range [0 .. elements - 1].
+ * E.g. the library uses this to track hardware channel allocation.
+ *
+ * The Resource class does not allocate the hardware channels or other
+ * resources; it just tracks which indices were marked in use by
+ * Allocate and not yet freed by Free.
+ */
+class Resource : public ErrorBase {
+ public:
+  virtual ~Resource() = default;
+
+  Resource(const Resource&) = delete;
+  Resource& operator=(const Resource&) = delete;
+
+  static void CreateResourceObject(std::unique_ptr<Resource>& r,
+                                   uint32_t elements);
+  explicit Resource(uint32_t size);
+  uint32_t Allocate(const std::string& resourceDesc);
+  uint32_t Allocate(uint32_t index, const std::string& resourceDesc);
+  void Free(uint32_t index);
+
+ private:
+  std::vector<bool> m_isAllocated;
+  priority_recursive_mutex m_allocateLock;
+
+  static priority_recursive_mutex m_createLock;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/RobotState.h b/wpilibc/shared/include/RobotState.h
new file mode 100644
index 0000000..195bb62
--- /dev/null
+++ b/wpilibc/shared/include/RobotState.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 <memory>
+
+namespace frc {
+
+class RobotStateInterface {
+ public:
+  virtual ~RobotStateInterface() = default;
+  virtual bool IsDisabled() const = 0;
+  virtual bool IsEnabled() const = 0;
+  virtual bool IsOperatorControl() const = 0;
+  virtual bool IsAutonomous() const = 0;
+  virtual bool IsTest() const = 0;
+};
+
+class RobotState {
+ private:
+  static std::shared_ptr<RobotStateInterface> impl;
+
+ public:
+  static void SetImplementation(RobotStateInterface& i);
+  static void SetImplementation(std::shared_ptr<RobotStateInterface> i);
+  static bool IsDisabled();
+  static bool IsEnabled();
+  static bool IsOperatorControl();
+  static bool IsAutonomous();
+  static bool IsTest();
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/SmartDashboard/NamedSendable.h b/wpilibc/shared/include/SmartDashboard/NamedSendable.h
new file mode 100644
index 0000000..759447f
--- /dev/null
+++ b/wpilibc/shared/include/SmartDashboard/NamedSendable.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2012-2017. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared 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 "SmartDashboard/Sendable.h"
+
+namespace frc {
+
+/**
+ * The interface for sendable objects that gives the sendable a default name in
+ * the Smart Dashboard
+ *
+ */
+class NamedSendable : public Sendable {
+ public:
+  /**
+   * @return the name of the subtable of SmartDashboard that the Sendable object
+   *         will use
+   */
+  virtual std::string GetName() const = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/SmartDashboard/Sendable.h b/wpilibc/shared/include/SmartDashboard/Sendable.h
new file mode 100644
index 0000000..d7ca758
--- /dev/null
+++ b/wpilibc/shared/include/SmartDashboard/Sendable.h
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <memory>
+#include <string>
+
+#include "tables/ITable.h"
+
+namespace frc {
+
+class Sendable {
+ public:
+  /**
+   * Initializes a table for this sendable object.
+   * @param subtable The table to put the values in.
+   */
+  virtual void InitTable(std::shared_ptr<ITable> subtable) = 0;
+
+  /**
+   * @return the table that is currently associated with the sendable
+   */
+  virtual std::shared_ptr<ITable> GetTable() const = 0;
+
+  /**
+   * @return the string representation of the named data type that will be used
+   *         by the smart dashboard for this sendable
+   */
+  virtual std::string GetSmartDashboardType() const = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/SmartDashboard/SendableChooser.h b/wpilibc/shared/include/SmartDashboard/SendableChooser.h
new file mode 100644
index 0000000..5dbee54
--- /dev/null
+++ b/wpilibc/shared/include/SmartDashboard/SendableChooser.h
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <memory>
+#include <string>
+
+#include "SmartDashboard/SendableChooserBase.h"
+#include "llvm/StringMap.h"
+#include "llvm/StringRef.h"
+#include "tables/ITable.h"
+
+namespace frc {
+
+/**
+ * The {@link SendableChooser} class is a useful tool for presenting a selection
+ * of options to the {@link SmartDashboard}.
+ *
+ * <p>For instance, you may wish to be able to select between multiple
+ * autonomous modes. You can do this by putting every possible {@link Command}
+ * you want to run as an autonomous into a {@link SendableChooser} and then put
+ * it into the {@link SmartDashboard} to have a list of options appear on the
+ * laptop.  Once autonomous starts, simply ask the {@link SendableChooser} what
+ * the selected value is.</p>
+ *
+ * @tparam T The type of values to be stored
+ * @see SmartDashboard
+ */
+template <class T>
+class SendableChooser : public SendableChooserBase {
+ public:
+  virtual ~SendableChooser() = default;
+
+  void AddObject(llvm::StringRef name, const T& object);
+  void AddDefault(llvm::StringRef name, const T& object);
+  T GetSelected();
+
+  void InitTable(std::shared_ptr<ITable> subtable) override;
+
+ private:
+  llvm::StringMap<T> m_choices;
+};
+
+}  // namespace frc
+
+#include "SendableChooser.inc"
diff --git a/wpilibc/shared/include/SmartDashboard/SendableChooser.inc b/wpilibc/shared/include/SmartDashboard/SendableChooser.inc
new file mode 100644
index 0000000..ba9363f
--- /dev/null
+++ b/wpilibc/shared/include/SmartDashboard/SendableChooser.inc
@@ -0,0 +1,83 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <algorithm>
+#include <memory>
+#include <string>
+#include <utility>
+#include <vector>
+
+namespace frc {
+
+/**
+ * Adds the given object to the list of options.
+ *
+ * On the {@link SmartDashboard} on the desktop, the object will appear as the
+ * given name.
+ *
+ * @param name   the name of the option
+ * @param object the option
+ */
+template <class T>
+void SendableChooser<T>::AddObject(llvm::StringRef name, const T& object) {
+  m_choices[name] = object;
+}
+
+/**
+ * Add the given object to the list of options and marks it as the default.
+ *
+ * Functionally, this is very close to {@link SendableChooser#AddObject(const
+ * char *name, void *object) AddObject(...)} except that it will use this as
+ * the default option if none other is explicitly selected.
+ *
+ * @param name   the name of the option
+ * @param object the option
+ */
+template <class T>
+void SendableChooser<T>::AddDefault(llvm::StringRef name, const T& object) {
+  m_defaultChoice = name;
+  AddObject(name, object);
+}
+
+/**
+ * Returns the selected option.
+ *
+ * If there is none selected, it will return the default.  If there is none
+ * selected and no default, then it will return {@code nullptr}.
+ *
+ * @return the option selected
+ */
+template <class T>
+T SendableChooser<T>::GetSelected() {
+  std::string selected = m_table->GetString(kSelected, m_defaultChoice);
+  if (selected == "") {
+    return nullptr;
+  } else {
+    return m_choices[selected];
+  }
+}
+
+template <class T>
+void SendableChooser<T>::InitTable(std::shared_ptr<ITable> subtable) {
+  std::vector<std::string> keys;
+  m_table = subtable;
+  if (m_table != nullptr) {
+    for (const auto& choice : m_choices) {
+      keys.push_back(choice.first());
+    }
+
+    // Unlike std::map, llvm::StringMap elements are not sorted
+    std::sort(keys.begin(), keys.end());
+
+    m_table->PutValue(kOptions, nt::Value::MakeStringArray(std::move(keys)));
+    m_table->PutString(kDefault, m_defaultChoice);
+  }
+}
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/SmartDashboard/SendableChooserBase.h b/wpilibc/shared/include/SmartDashboard/SendableChooserBase.h
new file mode 100644
index 0000000..04102ee
--- /dev/null
+++ b/wpilibc/shared/include/SmartDashboard/SendableChooserBase.h
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2017. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include "SmartDashboard/Sendable.h"
+#include "tables/ITable.h"
+
+namespace frc {
+
+/**
+ * This class is a non-template base class for {@link SendableChooser}.
+ *
+ * It contains static, non-templated variables to avoid their duplication in the
+ * template class.
+ */
+class SendableChooserBase : public Sendable {
+ public:
+  virtual ~SendableChooserBase() = default;
+
+  std::shared_ptr<ITable> GetTable() const override;
+  std::string GetSmartDashboardType() const override;
+
+ protected:
+  static const char* kDefault;
+  static const char* kOptions;
+  static const char* kSelected;
+
+  std::string m_defaultChoice;
+  std::shared_ptr<ITable> m_table;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/SmartDashboard/SmartDashboard.h b/wpilibc/shared/include/SmartDashboard/SmartDashboard.h
new file mode 100644
index 0000000..8656d73
--- /dev/null
+++ b/wpilibc/shared/include/SmartDashboard/SmartDashboard.h
@@ -0,0 +1,100 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SensorBase.h"
+#include "SmartDashboard/NamedSendable.h"
+#include "SmartDashboard/Sendable.h"
+#include "tables/ITable.h"
+
+namespace frc {
+
+class SmartDashboard : public SensorBase {
+ public:
+  static void init();
+
+  static bool ContainsKey(llvm::StringRef key);
+
+  static std::vector<std::string> GetKeys(int types = 0);
+
+  static void SetPersistent(llvm::StringRef key);
+  static void ClearPersistent(llvm::StringRef key);
+  static bool IsPersistent(llvm::StringRef key);
+
+  static void SetFlags(llvm::StringRef key, unsigned int flags);
+  static void ClearFlags(llvm::StringRef key, unsigned int flags);
+  static unsigned int GetFlags(llvm::StringRef key);
+
+  static void Delete(llvm::StringRef key);
+
+  static void PutData(llvm::StringRef key, Sendable* data);
+  static void PutData(NamedSendable* value);
+  static Sendable* GetData(llvm::StringRef keyName);
+
+  static bool PutBoolean(llvm::StringRef keyName, bool value);
+  static bool SetDefaultBoolean(llvm::StringRef key, bool defaultValue);
+  static bool GetBoolean(llvm::StringRef keyName, bool defaultValue);
+
+  static bool PutNumber(llvm::StringRef keyName, double value);
+  static bool SetDefaultNumber(llvm::StringRef key, double defaultValue);
+  static double GetNumber(llvm::StringRef keyName, double defaultValue);
+
+  static bool PutString(llvm::StringRef keyName, llvm::StringRef value);
+  static bool SetDefaultString(llvm::StringRef key,
+                               llvm::StringRef defaultValue);
+  static std::string GetString(llvm::StringRef keyName,
+                               llvm::StringRef defaultValue);
+
+  static bool PutBooleanArray(llvm::StringRef key, llvm::ArrayRef<int> value);
+  static bool SetDefaultBooleanArray(llvm::StringRef key,
+                                     llvm::ArrayRef<int> defaultValue);
+  static std::vector<int> GetBooleanArray(llvm::StringRef key,
+                                          llvm::ArrayRef<int> defaultValue);
+
+  static bool PutNumberArray(llvm::StringRef key, llvm::ArrayRef<double> value);
+  static bool SetDefaultNumberArray(llvm::StringRef key,
+                                    llvm::ArrayRef<double> defaultValue);
+  static std::vector<double> GetNumberArray(
+      llvm::StringRef key, llvm::ArrayRef<double> defaultValue);
+
+  static bool PutStringArray(llvm::StringRef key,
+                             llvm::ArrayRef<std::string> value);
+  static bool SetDefaultStringArray(llvm::StringRef key,
+                                    llvm::ArrayRef<std::string> defaultValue);
+  static std::vector<std::string> GetStringArray(
+      llvm::StringRef key, llvm::ArrayRef<std::string> defaultValue);
+
+  static bool PutRaw(llvm::StringRef key, llvm::StringRef value);
+  static bool SetDefaultRaw(llvm::StringRef key, llvm::StringRef defaultValue);
+  static std::string GetRaw(llvm::StringRef key, llvm::StringRef defaultValue);
+
+  static bool PutValue(llvm::StringRef keyName,
+                       std::shared_ptr<nt::Value> value);
+  static bool SetDefaultValue(llvm::StringRef key,
+                              std::shared_ptr<nt::Value> defaultValue);
+  static std::shared_ptr<nt::Value> GetValue(llvm::StringRef keyName);
+
+ private:
+  virtual ~SmartDashboard() = default;
+
+  /** The {@link NetworkTable} used by {@link SmartDashboard} */
+  static std::shared_ptr<ITable> m_table;
+
+  /**
+   * A map linking tables in the SmartDashboard to the
+   * {@link SmartDashboardData} objects they came from.
+   */
+  static std::map<std::shared_ptr<ITable>, Sendable*> m_tablesToData;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Timer.h b/wpilibc/shared/include/Timer.h
new file mode 100644
index 0000000..c71e3c8
--- /dev/null
+++ b/wpilibc/shared/include/Timer.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 "Base.h"
+#include "HAL/cpp/priority_mutex.h"
+
+namespace frc {
+
+typedef void (*TimerInterruptHandler)(void* param);
+
+void Wait(double seconds);
+double GetClock();
+double GetTime();
+
+/**
+ * Timer objects measure accumulated time in seconds.
+ * The timer object functions like a stopwatch. It can be started, stopped, and
+ * cleared. When the timer is running its value counts up in seconds. When
+ * stopped, the timer holds the current value. The implementation simply records
+ * the time when started and subtracts the current time whenever the value is
+ * requested.
+ */
+class Timer {
+ public:
+  Timer();
+  virtual ~Timer() = default;
+
+  Timer(const Timer&) = delete;
+  Timer& operator=(const Timer&) = delete;
+
+  double Get() const;
+  void Reset();
+  void Start();
+  void Stop();
+  bool HasPeriodPassed(double period);
+
+  static double GetFPGATimestamp();
+  static double GetPPCTimestamp();
+  static double GetMatchTime();
+
+  // The time, in seconds, at which the 32-bit FPGA timestamp rolls over to 0
+  static const double kRolloverTime;
+
+ private:
+  double m_startTime = 0.0;
+  double m_accumulatedTime = 0.0;
+  bool m_running = false;
+  mutable priority_mutex m_mutex;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/Utility.h b/wpilibc/shared/include/Utility.h
new file mode 100644
index 0000000..bf97692
--- /dev/null
+++ b/wpilibc/shared/include/Utility.h
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/** @file
+ * Contains global utility functions
+ */
+
+#include <stdint.h>
+
+#include <string>
+
+#include "llvm/StringRef.h"
+
+#define wpi_assert(condition) \
+  wpi_assert_impl(condition, #condition, "", __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertWithMessage(condition, message)                     \
+  wpi_assert_impl(condition, #condition, message, __FILE__, __LINE__, \
+                  __FUNCTION__)
+
+#define wpi_assertEqual(a, b) \
+  wpi_assertEqual_impl(a, b, #a, #b, "", __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertEqualWithMessage(a, b, message) \
+  wpi_assertEqual_impl(a, b, #a, #b, message, __FILE__, __LINE__, __FUNCTION__)
+
+#define wpi_assertNotEqual(a, b) \
+  wpi_assertNotEqual_impl(a, b, #a, #b, "", __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertNotEqualWithMessage(a, b, message)                 \
+  wpi_assertNotEqual_impl(a, b, #a, #b, message, __FILE__, __LINE__, \
+                          __FUNCTION__)
+
+bool wpi_assert_impl(bool conditionValue, llvm::StringRef conditionText,
+                     llvm::StringRef message, llvm::StringRef fileName,
+                     int lineNumber, llvm::StringRef funcName);
+bool wpi_assertEqual_impl(int valueA, int valueB, llvm::StringRef valueAString,
+                          llvm::StringRef valueBString, llvm::StringRef message,
+                          llvm::StringRef fileName, int lineNumber,
+                          llvm::StringRef funcName);
+bool wpi_assertNotEqual_impl(int valueA, int valueB,
+                             llvm::StringRef valueAString,
+                             llvm::StringRef valueBString,
+                             llvm::StringRef message, llvm::StringRef fileName,
+                             int lineNumber, llvm::StringRef funcName);
+
+void wpi_suspendOnAssertEnabled(bool enabled);
+
+namespace frc {
+
+int GetFPGAVersion();
+int64_t GetFPGARevision();
+uint64_t GetFPGATime();
+bool GetUserButton();
+std::string GetStackTrace(int offset);
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/WPIErrors.h b/wpilibc/shared/include/WPIErrors.h
new file mode 100644
index 0000000..ece177c
--- /dev/null
+++ b/wpilibc/shared/include/WPIErrors.h
@@ -0,0 +1,104 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#ifdef WPI_ERRORS_DEFINE_STRINGS
+#define S(label, offset, message)            \
+  const char* wpi_error_s_##label = message; \
+  const int wpi_error_value_##label = offset
+#else
+#define S(label, offset, message)         \
+  extern const char* wpi_error_s_##label; \
+  const int wpi_error_value_##label = offset
+#endif
+
+/*
+ * Fatal errors
+ */
+S(ModuleIndexOutOfRange, -1,
+  "Allocating module that is out of range or not found");
+S(ChannelIndexOutOfRange, -1, "Allocating channel that is out of range");
+S(NotAllocated, -2, "Attempting to free unallocated resource");
+S(ResourceAlreadyAllocated, -3, "Attempted to reuse an allocated resource");
+S(NoAvailableResources, -4, "No available resources to allocate");
+S(NullParameter, -5, "A pointer parameter to a method is nullptr");
+S(Timeout, -6, "A timeout has been exceeded");
+S(CompassManufacturerError, -7, "Compass manufacturer doesn't match HiTechnic");
+S(CompassTypeError, -8,
+  "Compass type doesn't match expected type for HiTechnic compass");
+S(IncompatibleMode, -9, "The object is in an incompatible mode");
+S(AnalogTriggerLimitOrderError, -10,
+  "AnalogTrigger limits error.  Lower limit > Upper Limit");
+S(AnalogTriggerPulseOutputError, -11,
+  "Attempted to read AnalogTrigger pulse output.");
+S(TaskError, -12, "Task can't be started");
+S(TaskIDError, -13, "Task error: Invalid ID.");
+S(TaskDeletedError, -14, "Task error: Task already deleted.");
+S(TaskOptionsError, -15, "Task error: Invalid options.");
+S(TaskMemoryError, -16, "Task can't be started due to insufficient memory.");
+S(TaskPriorityError, -17, "Task error: Invalid priority [1-255].");
+S(DriveUninitialized, -18, "RobotDrive not initialized for the C interface");
+S(CompressorNonMatching, -19,
+  "Compressor slot/channel doesn't match previous instance");
+S(CompressorAlreadyDefined, -20, "Creating a second compressor instance");
+S(CompressorUndefined, -21,
+  "Using compressor functions without defining compressor");
+S(InconsistentArrayValueAdded, -22,
+  "When packing data into an array to the dashboard, not all values added were "
+  "of the same type.");
+S(MismatchedComplexTypeClose, -23,
+  "When packing data to the dashboard, a Close for a complex type was called "
+  "without a matching Open.");
+S(DashboardDataOverflow, -24,
+  "When packing data to the dashboard, too much data was packed and the buffer "
+  "overflowed.");
+S(DashboardDataCollision, -25,
+  "The same buffer was used for packing data and for printing.");
+S(EnhancedIOMissing, -26, "IO is not attached or Enhanced IO is not enabled.");
+S(LineNotOutput, -27,
+  "Cannot SetDigitalOutput for a line not configured for output.");
+S(ParameterOutOfRange, -28, "A parameter is out of range.");
+S(SPIClockRateTooLow, -29, "SPI clock rate was below the minimum supported");
+S(JaguarVersionError, -30, "Jaguar firmware version error");
+S(JaguarMessageNotFound, -31, "Jaguar message not found");
+S(NetworkTablesReadError, -40, "Error reading NetworkTables socket");
+S(NetworkTablesBufferFull, -41, "Buffer full writing to NetworkTables socket");
+S(NetworkTablesWrongType, -42,
+  "The wrong type was read from the NetworkTables entry");
+S(NetworkTablesCorrupt, -43, "NetworkTables data stream is corrupt");
+S(SmartDashboardMissingKey, -43, "SmartDashboard data does not exist");
+S(CommandIllegalUse, -50, "Illegal use of Command");
+S(UnsupportedInSimulation, -80, "Unsupported in simulation");
+S(CameraServerError, -90, "CameraServer error");
+
+/*
+ * Warnings
+ */
+S(SampleRateTooHigh, 1, "Analog module sample rate is too high");
+S(VoltageOutOfRange, 2,
+  "Voltage to convert to raw value is out of range [-10; 10]");
+S(CompressorTaskError, 3, "Compressor task won't start");
+S(LoopTimingError, 4, "Digital module loop timing is not the expected value");
+S(NonBinaryDigitalValue, 5, "Digital output value is not 0 or 1");
+S(IncorrectBatteryChannel, 6,
+  "Battery measurement channel is not correct value");
+S(BadJoystickIndex, 7, "Joystick index is out of range, should be 0-3");
+S(BadJoystickAxis, 8, "Joystick axis or POV is out of range");
+S(InvalidMotorIndex, 9, "Motor index is out of range, should be 0-3");
+S(DriverStationTaskError, 10, "Driver Station task won't start");
+S(EnhancedIOPWMPeriodOutOfRange, 11,
+  "Driver Station Enhanced IO PWM Output period out of range.");
+S(SPIWriteNoMOSI, 12, "Cannot write to SPI port with no MOSI output");
+S(SPIReadNoMISO, 13, "Cannot read from SPI port with no MISO input");
+S(SPIReadNoData, 14, "No data available to read from SPI");
+S(IncompatibleState, 15,
+  "Incompatible State: The operation cannot be completed");
+
+#undef S
diff --git a/wpilibc/shared/include/WPILibVersion.h b/wpilibc/shared/include/WPILibVersion.h
new file mode 100644
index 0000000..80c4a3c
--- /dev/null
+++ b/wpilibc/shared/include/WPILibVersion.h
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/*
+ * The corresponding WPILibVersion.cpp file is autogenerated by the build
+ * system. If it does not exist, make sure that you run a build.
+ */
+extern const char* WPILibVersion;
diff --git a/wpilibc/shared/include/XboxController.h b/wpilibc/shared/include/XboxController.h
new file mode 100644
index 0000000..d60d656
--- /dev/null
+++ b/wpilibc/shared/include/XboxController.h
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ErrorBase.h"
+#include "GamepadBase.h"
+
+namespace frc {
+
+class DriverStation;
+
+/**
+ * Handle input from Xbox 360 or Xbox One controllers connected to the Driver
+ * Station.
+ *
+ * This class handles Xbox input that comes from the Driver Station. Each time a
+ * value is requested the most recent value is returend. There is a single class
+ * instance for each controller and the mapping of ports to hardware buttons
+ * depends on the code in the Driver Station.
+ */
+class XboxController : public GamepadBase, public ErrorBase {
+ public:
+  explicit XboxController(int port);
+  virtual ~XboxController() = default;
+
+  XboxController(const XboxController&) = delete;
+  XboxController& operator=(const XboxController&) = delete;
+
+  double GetX(JoystickHand hand) const override;
+  double GetY(JoystickHand hand) const override;
+
+  bool GetBumper(JoystickHand hand) const override;
+  bool GetStickButton(JoystickHand hand) const override;
+
+  virtual double GetTriggerAxis(JoystickHand hand) const;
+
+  bool GetAButton() const;
+  bool GetBButton() const;
+  bool GetXButton() const;
+  bool GetYButton() const;
+  bool GetBackButton() const;
+  bool GetStartButton() const;
+
+ private:
+  DriverStation& m_ds;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/interfaces/Accelerometer.h b/wpilibc/shared/include/interfaces/Accelerometer.h
new file mode 100644
index 0000000..f8491eb
--- /dev/null
+++ b/wpilibc/shared/include/interfaces/Accelerometer.h
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* 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
+
+namespace frc {
+
+/**
+ * Interface for 3-axis accelerometers
+ */
+class Accelerometer {
+ public:
+  virtual ~Accelerometer() = default;
+
+  enum Range { kRange_2G = 0, kRange_4G = 1, kRange_8G = 2, kRange_16G = 3 };
+
+  /**
+   * Common interface for setting the measuring range of an accelerometer.
+   *
+   * @param range The maximum acceleration, positive or negative, that the
+   * accelerometer will measure.  Not all accelerometers support all ranges.
+   */
+  virtual void SetRange(Range range) = 0;
+
+  /**
+   * Common interface for getting the x axis acceleration
+   *
+   * @return The acceleration along the x axis in g-forces
+   */
+  virtual double GetX() = 0;
+
+  /**
+   * Common interface for getting the y axis acceleration
+   *
+   * @return The acceleration along the y axis in g-forces
+   */
+  virtual double GetY() = 0;
+
+  /**
+   * Common interface for getting the z axis acceleration
+   *
+   * @return The acceleration along the z axis in g-forces
+   */
+  virtual double GetZ() = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/interfaces/Gyro.h b/wpilibc/shared/include/interfaces/Gyro.h
new file mode 100644
index 0000000..6ae2f65
--- /dev/null
+++ b/wpilibc/shared/include/interfaces/Gyro.h
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* 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
+
+namespace frc {
+
+/**
+ * Interface for yaw rate gyros
+ */
+class Gyro {
+ public:
+  virtual ~Gyro() = default;
+
+  /**
+   * Calibrate the gyro by running for a number of samples and computing the
+   * center value. Then use the center value as the Accumulator center value for
+   * subsequent measurements. It's important to make sure that the robot is not
+   * moving while the centering calculations are in progress, this is typically
+   * done when the robot is first turned on while it's sitting at rest before
+   * the competition starts.
+   */
+  virtual void Calibrate() = 0;
+
+  /**
+   * Reset the gyro. Resets the gyro to a heading of zero. This can be used if
+   * there is significant drift in the gyro and it needs to be recalibrated
+   * after it has been running.
+   */
+  virtual void Reset() = 0;
+
+  /**
+   * Return the actual angle in degrees that the robot is currently facing.
+   *
+   * The angle is based on the current accumulator value corrected by the
+   * oversampling rate, the gyro type and the A/D calibration values. The angle
+   * is continuous, that is it will continue from 360 to 361 degrees. This
+   * allows algorithms that wouldn't want to see a discontinuity in the gyro
+   * output as it sweeps past from 360 to 0 on the second time around.
+   *
+   * @return the current heading of the robot in degrees. This heading is based
+   *         on integration of the returned rate from the gyro.
+   */
+  virtual double GetAngle() const = 0;
+
+  /**
+   * Return the rate of rotation of the gyro
+   *
+   * The rate is based on the most recent reading of the gyro analog value
+   *
+   * @return the current rate in degrees per second
+   */
+  virtual double GetRate() const = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/shared/include/interfaces/Potentiometer.h b/wpilibc/shared/include/interfaces/Potentiometer.h
new file mode 100644
index 0000000..b50a849
--- /dev/null
+++ b/wpilibc/shared/include/interfaces/Potentiometer.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "PIDSource.h"
+
+namespace frc {
+
+/**
+ * Interface for potentiometers.
+ */
+class Potentiometer : public PIDSource {
+ public:
+  virtual ~Potentiometer() = default;
+
+  /**
+   * Common interface for getting the current value of a potentiometer.
+   *
+   * @return The current set speed.  Value is between -1.0 and 1.0.
+   */
+  virtual double Get() const = 0;
+
+  void SetPIDSourceType(PIDSourceType pidSource) override;
+};
+
+}  // namespace frc