Rename our allwpilib (which is now 2020) to not have 2019 in the name

Change-Id: I3c07f85ed32ab8b97db765a9b43f2a6ce7da964a
diff --git a/wpilibc/CMakeLists.txt b/wpilibc/CMakeLists.txt
new file mode 100644
index 0000000..977200a
--- /dev/null
+++ b/wpilibc/CMakeLists.txt
@@ -0,0 +1,46 @@
+project(wpilibc)
+
+include(CompileWarnings)
+include(AddTest)
+
+find_package( OpenCV REQUIRED )
+
+configure_file(src/generate/WPILibVersion.cpp.in WPILibVersion.cpp)
+
+file(GLOB_RECURSE
+    wpilibc_native_src src/main/native/cpp/*.cpp src/main/native/cppcs/*.cpp)
+
+add_library(wpilibc ${wpilibc_native_src} ${CMAKE_CURRENT_BINARY_DIR}/WPILibVersion.cpp)
+set_target_properties(wpilibc PROPERTIES DEBUG_POSTFIX "d")
+
+target_include_directories(wpilibc PUBLIC
+                $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
+                            $<INSTALL_INTERFACE:${include_dest}/wpilibc>)
+wpilib_target_warnings(wpilibc)
+target_link_libraries(wpilibc PUBLIC cameraserver hal ntcore cscore wpiutil ${OpenCV_LIBS})
+
+set_property(TARGET wpilibc PROPERTY FOLDER "libraries")
+
+install(TARGETS wpilibc EXPORT wpilibc DESTINATION "${main_lib_dest}")
+install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpilibc")
+
+if (MSVC OR FLAT_INSTALL_WPILIB)
+    set (wpilibc_config_dir ${wpilib_dest})
+else()
+    set (wpilibc_config_dir share/wpilibc)
+endif()
+
+configure_file(wpilibc-config.cmake.in ${CMAKE_BINARY_DIR}/wpilibc-config.cmake )
+install(FILES ${CMAKE_BINARY_DIR}/wpilibc-config.cmake DESTINATION ${wpilibc_config_dir})
+install(EXPORT wpilibc DESTINATION ${wpilibc_config_dir})
+
+if (WITH_TESTS)
+    wpilib_add_test(wpilibc src/test/native/cpp)
+    target_include_directories(wpilibc_test PRIVATE src/test/native/include)
+    target_link_libraries(wpilibc_test wpilibc gmock_main)
+    if (NOT MSVC)
+        target_compile_options(wpilibc_test PRIVATE -Wno-error)
+    else()
+        target_compile_options(wpilibc_test PRIVATE /WX-)
+    endif()
+endif()
diff --git a/wpilibc/build.gradle b/wpilibc/build.gradle
new file mode 100644
index 0000000..4ee5766
--- /dev/null
+++ b/wpilibc/build.gradle
@@ -0,0 +1,247 @@
+apply plugin: 'cpp'
+apply plugin: 'c'
+apply plugin: 'google-test-test-suite'
+apply plugin: 'visual-studio'
+apply plugin: 'edu.wpi.first.NativeUtils'
+apply plugin: SingleNativeBuild
+apply plugin: ExtraTasks
+
+ext {
+    nativeName = 'wpilibc'
+}
+
+apply from: "${rootDir}/shared/config.gradle"
+
+def wpilibVersionFileInput = file("src/generate/WPILibVersion.cpp.in")
+def wpilibVersionFileOutput = file("$buildDir/generated/cpp/WPILibVersion.cpp")
+
+task generateCppVersion() {
+    description = 'Generates the wpilib version class'
+    group = 'WPILib'
+
+    outputs.file wpilibVersionFileOutput
+    inputs.file wpilibVersionFileInput
+
+    if (wpilibVersioning.releaseMode) {
+        outputs.upToDateWhen { false }
+    }
+
+    // We follow a simple set of checks to determine whether we should generate a new version file:
+    // 1. If the release type is not development, we generate a new version file
+    // 2. If there is no generated version number, we generate a new version file
+    // 3. If there is a generated build number, and the release type is development, then we will
+    //    only generate if the publish task is run.
+    doLast {
+        def version = wpilibVersioning.version.get()
+        println "Writing version ${version} to $wpilibVersionFileOutput"
+
+        if (wpilibVersionFileOutput.exists()) {
+            wpilibVersionFileOutput.delete()
+        }
+        def read = wpilibVersionFileInput.text.replace('${wpilib_version}', version)
+        wpilibVersionFileOutput.write(read)
+    }
+}
+
+gradle.taskGraph.addTaskExecutionGraphListener { graph ->
+    def willPublish = graph.hasTask(publish)
+    if (willPublish) {
+        generateCppVersion.outputs.upToDateWhen { false }
+    }
+}
+
+project(':').libraryBuild.dependsOn build
+
+ext {
+    staticGtestConfigs = [:]
+}
+
+staticGtestConfigs["${nativeName}Test"] = []
+
+apply from: "${rootDir}/shared/googletest.gradle"
+
+apply plugin: DisableBuildingGTest
+
+nativeUtils.exportsConfigs {
+    wpilibc {
+        x86ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                            '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                            '_TI5?AVfailure', '_CT??_R0?AVout_of_range', '_CTA3?AVout_of_range',
+                            '_TI3?AVout_of_range', '_CT??_R0?AVbad_cast']
+        x64ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                            '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                            '_TI5?AVfailure', '_CT??_R0?AVout_of_range', '_CTA3?AVout_of_range',
+                            '_TI3?AVout_of_range', '_CT??_R0?AVbad_cast']
+    }
+}
+
+model {
+    components {
+        "${nativeName}Base"(NativeLibrarySpec) {
+            sources {
+                cpp {
+                    source {
+                        srcDirs = ['src/main/native/cpp', "$buildDir/generated/cpp"]
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include'
+                    }
+                }
+            }
+            binaries.all {
+                if (it instanceof SharedLibraryBinarySpec) {
+                    it.buildable = false
+                    return
+                }
+                cppCompiler.define 'DYNAMIC_CAMERA_SERVER'
+                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                project(':hal').addHalDependency(it, 'shared')
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+            }
+        }
+        "${nativeName}"(NativeLibrarySpec) {
+            sources {
+                cpp {
+                    source {
+                        srcDirs "src/main/native/cppcs"
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', '../cameraserver/src/main/native/include'
+                    }
+                }
+            }
+            binaries.all {
+                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                project(':hal').addHalDependency(it, 'shared')
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+
+                if (it instanceof SharedLibraryBinarySpec) {
+                    cppCompiler.define 'DYNAMIC_CAMERA_SERVER'
+                    if (buildType == buildTypes.debug) {
+                        cppCompiler.define 'DYNAMIC_CAMERA_SERVER_DEBUG'
+                    }
+                } else {
+                    lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                    lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+                    nativeUtils.useRequiredLibrary(it, 'opencv_shared')
+                }
+
+            }
+            appendDebugPathToBinaries(binaries)
+        }
+        // By default, a development executable will be generated. This is to help the case of
+        // testing specific functionality of the library.
+        "${nativeName}Dev"(NativeExecutableSpec) {
+            targetBuildTypes 'debug'
+            sources {
+                cpp {
+                    source {
+                        srcDirs 'src/dev/native/cpp'
+                        include '**/*.cpp'
+                        lib library: 'wpilibc'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/dev/native/include'
+                    }
+                }
+            }
+            binaries.all {
+                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                project(':hal').addHalDependency(it, 'shared')
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+                nativeUtils.useRequiredLibrary(it, 'opencv_shared')
+                if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
+                    nativeUtils.useRequiredLibrary(it, 'netcomm_shared', 'chipobject_shared', 'visa_shared', 'ni_runtime_shared')
+                }
+            }
+        }
+    }
+    testSuites {
+        "${nativeName}Test"(GoogleTestTestSuiteSpec) {
+            for(NativeComponentSpec c : $.components) {
+                if (c.name == nativeName) {
+                    testing c
+                    break
+                }
+            }
+            sources {
+                cpp {
+                    source {
+                        srcDirs 'src/test/native/cpp'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/test/native/include', 'src/main/native/cpp'
+                    }
+                }
+                c {
+                    source {
+                        srcDirs 'src/test/native/c'
+                        include '**/*.c'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/test/native/include', 'src/main/native/c'
+                    }
+                }
+            }
+        }
+    }
+    binaries {
+        all {
+            tasks.withType(CppCompile) {
+                dependsOn generateCppVersion
+            }
+        }
+        withType(GoogleTestTestSuiteBinarySpec) {
+            lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+            lib project: ':cscore', library: 'cscore', linkage: 'shared'
+            project(':hal').addHalDependency(it, 'shared')
+            lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+            lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+            nativeUtils.useRequiredLibrary(it, 'opencv_shared')
+            lib library: nativeName, linkage: 'shared'
+            if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) {
+                nativeUtils.useRequiredLibrary(it, 'netcomm_shared', 'chipobject_shared', 'visa_shared', 'ni_runtime_shared')
+            }
+        }
+    }
+    tasks {
+        def c = $.components
+        project.tasks.create('runCpp', Exec) {
+            def found = false
+            c.each {
+                if (it in NativeExecutableSpec && it.name == "${nativeName}Dev") {
+                    it.binaries.each {
+                        if (!found) {
+                            def arch = it.targetPlatform.architecture.name
+                            if (arch == 'x86-64' || arch == 'x86') {
+                                dependsOn it.tasks.install
+
+                                found = true
+                            }
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
+
+apply from: "${rootDir}/shared/cppDesktopTestTask.gradle"
+
+tasks.withType(RunTestExecutable) {
+    args "--gtest_output=xml:test_detail.xml"
+    outputs.dir outputDir
+}
+
+apply from: 'publish.gradle'
+
+def oldWpilibVersionFile = file('src/main/native/cpp/WPILibVersion.cpp')
+
+clean {
+    delete oldWpilibVersionFile
+}
diff --git a/wpilibc/publish.gradle b/wpilibc/publish.gradle
new file mode 100644
index 0000000..025c09d
--- /dev/null
+++ b/wpilibc/publish.gradle
@@ -0,0 +1,67 @@
+apply plugin: 'maven-publish'
+
+def baseArtifactId = 'wpilibc-cpp'
+def artifactGroupId = 'edu.wpi.first.wpilibc'
+def zipBaseName = '_GROUP_edu_wpi_first_wpilibc_ID_wpilibc-cpp_CLS'
+
+def outputsFolder = file("$project.buildDir/outputs")
+
+task cppSourcesZip(type: Zip) {
+    destinationDirectory = outputsFolder
+    archiveBaseName = zipBaseName
+    classifier = "sources"
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/native/cpp') {
+        into '/'
+    }
+    from("$buildDir/generated/cpp") {
+        into '/'
+    }
+}
+
+cppSourcesZip.dependsOn generateCppVersion
+
+task cppHeadersZip(type: Zip) {
+    destinationDirectory = outputsFolder
+    archiveBaseName = zipBaseName
+    classifier = "headers"
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/native/include') {
+        into '/'
+    }
+}
+
+build.dependsOn cppHeadersZip
+build.dependsOn cppSourcesZip
+
+addTaskToCopyAllOutputs(cppHeadersZip)
+addTaskToCopyAllOutputs(cppSourcesZip)
+
+model {
+    publishing {
+        def wpilibCTaskList = createComponentZipTasks($.components, ['wpilibc'], zipBaseName, Zip, project, includeStandardZipFormat)
+
+        publications {
+            cpp(MavenPublication) {
+                wpilibCTaskList.each {
+                    artifact it
+                }
+
+                artifact cppHeadersZip
+                artifact cppSourcesZip
+
+                artifactId = baseArtifactId
+                groupId artifactGroupId
+                version wpilibVersioning.version.get()
+            }
+        }
+    }
+}
diff --git a/wpilibc/src/dev/native/cpp/main.cpp b/wpilibc/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..f1370bb
--- /dev/null
+++ b/wpilibc/src/dev/native/cpp/main.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <iostream>
+
+#include <hal/HALBase.h>
+
+#include "WPILibVersion.h"
+
+int main() {
+  std::cout << "Hello World" << std::endl;
+  std::cout << HAL_GetRuntimeType() << std::endl;
+  std::cout << GetWPILibVersion() << std::endl;
+  return 0;
+}
diff --git a/wpilibc/src/generate/WPILibVersion.cpp.in b/wpilibc/src/generate/WPILibVersion.cpp.in
new file mode 100644
index 0000000..b0a4490
--- /dev/null
+++ b/wpilibc/src/generate/WPILibVersion.cpp.in
@@ -0,0 +1,7 @@
+/*
+ * Autogenerated file! Do not manually edit this file. This version is regenerated
+ * any time the publish task is run, or when this file is deleted.
+ */
+const char* GetWPILibVersion() {
+  return "${wpilib_version}";
+}
diff --git a/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp b/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp
new file mode 100644
index 0000000..a760daa
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp
@@ -0,0 +1,88 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/ADXL345_I2C.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+ADXL345_I2C::ADXL345_I2C(I2C::Port port, Range range, int deviceAddress)
+    : m_i2c(port, deviceAddress),
+      m_simDevice("ADXL345_I2C", port, deviceAddress) {
+  if (m_simDevice) {
+    m_simRange =
+        m_simDevice.CreateEnum("Range", true, {"2G", "4G", "8G", "16G"}, 0);
+    m_simX = m_simDevice.CreateDouble("X Accel", false, 0.0);
+    m_simX = m_simDevice.CreateDouble("Y Accel", false, 0.0);
+    m_simZ = m_simDevice.CreateDouble("Z Accel", false, 0.0);
+  }
+  // Turn on the measurements
+  m_i2c.Write(kPowerCtlRegister, kPowerCtl_Measure);
+  // Specify the data format to read
+  SetRange(range);
+
+  HAL_Report(HALUsageReporting::kResourceType_ADXL345,
+             HALUsageReporting::kADXL345_I2C, 0);
+
+  SendableRegistry::GetInstance().AddLW(this, "ADXL345_I2C", port);
+}
+
+void ADXL345_I2C::SetRange(Range range) {
+  m_i2c.Write(kDataFormatRegister,
+              kDataFormat_FullRes | static_cast<uint8_t>(range));
+}
+
+double ADXL345_I2C::GetX() { return GetAcceleration(kAxis_X); }
+
+double ADXL345_I2C::GetY() { return GetAcceleration(kAxis_Y); }
+
+double ADXL345_I2C::GetZ() { return GetAcceleration(kAxis_Z); }
+
+double ADXL345_I2C::GetAcceleration(ADXL345_I2C::Axes axis) {
+  if (axis == kAxis_X && m_simX) return m_simX.Get();
+  if (axis == kAxis_Y && m_simY) return m_simY.Get();
+  if (axis == kAxis_Z && m_simZ) return m_simZ.Get();
+  int16_t rawAccel = 0;
+  m_i2c.Read(kDataRegister + static_cast<int>(axis), sizeof(rawAccel),
+             reinterpret_cast<uint8_t*>(&rawAccel));
+  return rawAccel * kGsPerLSB;
+}
+
+ADXL345_I2C::AllAxes ADXL345_I2C::GetAccelerations() {
+  AllAxes data;
+  if (m_simX && m_simY && m_simZ) {
+    data.XAxis = m_simX.Get();
+    data.YAxis = m_simY.Get();
+    data.ZAxis = m_simZ.Get();
+    return data;
+  }
+  int16_t rawData[3];
+  m_i2c.Read(kDataRegister, sizeof(rawData),
+             reinterpret_cast<uint8_t*>(rawData));
+
+  data.XAxis = rawData[0] * kGsPerLSB;
+  data.YAxis = rawData[1] * kGsPerLSB;
+  data.ZAxis = rawData[2] * kGsPerLSB;
+  return data;
+}
+
+void ADXL345_I2C::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("3AxisAccelerometer");
+  auto x = builder.GetEntry("X").GetHandle();
+  auto y = builder.GetEntry("Y").GetHandle();
+  auto z = builder.GetEntry("Z").GetHandle();
+  builder.SetUpdateTable([=]() {
+    auto data = GetAccelerations();
+    nt::NetworkTableEntry(x).SetDouble(data.XAxis);
+    nt::NetworkTableEntry(y).SetDouble(data.YAxis);
+    nt::NetworkTableEntry(z).SetDouble(data.ZAxis);
+  });
+}
diff --git a/wpilibc/src/main/native/cpp/ADXL345_SPI.cpp b/wpilibc/src/main/native/cpp/ADXL345_SPI.cpp
new file mode 100644
index 0000000..077a7ff
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/ADXL345_SPI.cpp
@@ -0,0 +1,117 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/ADXL345_SPI.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+ADXL345_SPI::ADXL345_SPI(SPI::Port port, ADXL345_SPI::Range range)
+    : m_spi(port), m_simDevice("ADXL345_SPI", port) {
+  if (m_simDevice) {
+    m_simRange =
+        m_simDevice.CreateEnum("Range", true, {"2G", "4G", "8G", "16G"}, 0);
+    m_simX = m_simDevice.CreateDouble("X Accel", false, 0.0);
+    m_simX = m_simDevice.CreateDouble("Y Accel", false, 0.0);
+    m_simZ = m_simDevice.CreateDouble("Z Accel", false, 0.0);
+  }
+  m_spi.SetClockRate(500000);
+  m_spi.SetMSBFirst();
+  m_spi.SetSampleDataOnTrailingEdge();
+  m_spi.SetClockActiveLow();
+  m_spi.SetChipSelectActiveHigh();
+
+  uint8_t commands[2];
+  // Turn on the measurements
+  commands[0] = kPowerCtlRegister;
+  commands[1] = kPowerCtl_Measure;
+  m_spi.Transaction(commands, commands, 2);
+
+  SetRange(range);
+
+  HAL_Report(HALUsageReporting::kResourceType_ADXL345,
+             HALUsageReporting::kADXL345_SPI);
+
+  SendableRegistry::GetInstance().AddLW(this, "ADXL345_SPI", port);
+}
+
+void ADXL345_SPI::SetRange(Range range) {
+  uint8_t commands[2];
+
+  // Specify the data format to read
+  commands[0] = kDataFormatRegister;
+  commands[1] = kDataFormat_FullRes | static_cast<uint8_t>(range & 0x03);
+  m_spi.Transaction(commands, commands, 2);
+
+  if (m_simRange) m_simRange.Set(range);
+}
+
+double ADXL345_SPI::GetX() { return GetAcceleration(kAxis_X); }
+
+double ADXL345_SPI::GetY() { return GetAcceleration(kAxis_Y); }
+
+double ADXL345_SPI::GetZ() { return GetAcceleration(kAxis_Z); }
+
+double ADXL345_SPI::GetAcceleration(ADXL345_SPI::Axes axis) {
+  if (axis == kAxis_X && m_simX) return m_simX.Get();
+  if (axis == kAxis_Y && m_simY) return m_simY.Get();
+  if (axis == kAxis_Z && m_simZ) return m_simZ.Get();
+  uint8_t buffer[3];
+  uint8_t command[3] = {0, 0, 0};
+  command[0] = (kAddress_Read | kAddress_MultiByte | kDataRegister) +
+               static_cast<uint8_t>(axis);
+  m_spi.Transaction(command, buffer, 3);
+
+  // Sensor is little endian... swap bytes
+  int16_t rawAccel = buffer[2] << 8 | buffer[1];
+  return rawAccel * kGsPerLSB;
+}
+
+ADXL345_SPI::AllAxes ADXL345_SPI::GetAccelerations() {
+  AllAxes data;
+  if (m_simX && m_simY && m_simZ) {
+    data.XAxis = m_simX.Get();
+    data.YAxis = m_simY.Get();
+    data.ZAxis = m_simZ.Get();
+    return data;
+  }
+
+  uint8_t dataBuffer[7] = {0, 0, 0, 0, 0, 0, 0};
+  int16_t rawData[3];
+
+  // Select the data address.
+  dataBuffer[0] = (kAddress_Read | kAddress_MultiByte | kDataRegister);
+  m_spi.Transaction(dataBuffer, dataBuffer, 7);
+
+  for (int i = 0; i < 3; i++) {
+    // Sensor is little endian... swap bytes
+    rawData[i] = dataBuffer[i * 2 + 2] << 8 | dataBuffer[i * 2 + 1];
+  }
+
+  data.XAxis = rawData[0] * kGsPerLSB;
+  data.YAxis = rawData[1] * kGsPerLSB;
+  data.ZAxis = rawData[2] * kGsPerLSB;
+
+  return data;
+}
+
+void ADXL345_SPI::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("3AxisAccelerometer");
+  auto x = builder.GetEntry("X").GetHandle();
+  auto y = builder.GetEntry("Y").GetHandle();
+  auto z = builder.GetEntry("Z").GetHandle();
+  builder.SetUpdateTable([=]() {
+    auto data = GetAccelerations();
+    nt::NetworkTableEntry(x).SetDouble(data.XAxis);
+    nt::NetworkTableEntry(y).SetDouble(data.YAxis);
+    nt::NetworkTableEntry(z).SetDouble(data.ZAxis);
+  });
+}
diff --git a/wpilibc/src/main/native/cpp/ADXL362.cpp b/wpilibc/src/main/native/cpp/ADXL362.cpp
new file mode 100644
index 0000000..6ed8c8c
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/ADXL362.cpp
@@ -0,0 +1,176 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/ADXL362.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/DriverStation.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+static constexpr int kRegWrite = 0x0A;
+static constexpr int kRegRead = 0x0B;
+
+static constexpr int kPartIdRegister = 0x02;
+static constexpr int kDataRegister = 0x0E;
+static constexpr int kFilterCtlRegister = 0x2C;
+static constexpr int kPowerCtlRegister = 0x2D;
+
+// static constexpr int kFilterCtl_Range2G = 0x00;
+// static constexpr int kFilterCtl_Range4G = 0x40;
+// static constexpr int kFilterCtl_Range8G = 0x80;
+static constexpr int kFilterCtl_ODR_100Hz = 0x03;
+
+static constexpr int kPowerCtl_UltraLowNoise = 0x20;
+// static constexpr int kPowerCtl_AutoSleep = 0x04;
+static constexpr int kPowerCtl_Measure = 0x02;
+
+ADXL362::ADXL362(Range range) : ADXL362(SPI::Port::kOnboardCS1, range) {}
+
+ADXL362::ADXL362(SPI::Port port, Range range)
+    : m_spi(port), m_simDevice("ADXL362", port) {
+  if (m_simDevice) {
+    m_simRange =
+        m_simDevice.CreateEnum("Range", true, {"2G", "4G", "8G", "16G"}, 0);
+    m_simX = m_simDevice.CreateDouble("X Accel", false, 0.0);
+    m_simX = m_simDevice.CreateDouble("Y Accel", false, 0.0);
+    m_simZ = m_simDevice.CreateDouble("Z Accel", false, 0.0);
+  }
+
+  m_spi.SetClockRate(3000000);
+  m_spi.SetMSBFirst();
+  m_spi.SetSampleDataOnTrailingEdge();
+  m_spi.SetClockActiveLow();
+  m_spi.SetChipSelectActiveLow();
+
+  uint8_t commands[3];
+  if (!m_simDevice) {
+    // Validate the part ID
+    commands[0] = kRegRead;
+    commands[1] = kPartIdRegister;
+    commands[2] = 0;
+    m_spi.Transaction(commands, commands, 3);
+    if (commands[2] != 0xF2) {
+      DriverStation::ReportError("could not find ADXL362");
+      m_gsPerLSB = 0.0;
+      return;
+    }
+  }
+
+  SetRange(range);
+
+  // Turn on the measurements
+  commands[0] = kRegWrite;
+  commands[1] = kPowerCtlRegister;
+  commands[2] = kPowerCtl_Measure | kPowerCtl_UltraLowNoise;
+  m_spi.Write(commands, 3);
+
+  HAL_Report(HALUsageReporting::kResourceType_ADXL362, port + 1);
+
+  SendableRegistry::GetInstance().AddLW(this, "ADXL362", port);
+}
+
+void ADXL362::SetRange(Range range) {
+  if (m_gsPerLSB == 0.0) return;
+
+  uint8_t commands[3];
+
+  switch (range) {
+    case kRange_2G:
+      m_gsPerLSB = 0.001;
+      break;
+    case kRange_4G:
+      m_gsPerLSB = 0.002;
+      break;
+    case kRange_8G:
+    case kRange_16G:  // 16G not supported; treat as 8G
+      m_gsPerLSB = 0.004;
+      break;
+  }
+
+  // Specify the data format to read
+  commands[0] = kRegWrite;
+  commands[1] = kFilterCtlRegister;
+  commands[2] =
+      kFilterCtl_ODR_100Hz | static_cast<uint8_t>((range & 0x03) << 6);
+  m_spi.Write(commands, 3);
+
+  if (m_simRange) m_simRange.Set(range);
+}
+
+double ADXL362::GetX() { return GetAcceleration(kAxis_X); }
+
+double ADXL362::GetY() { return GetAcceleration(kAxis_Y); }
+
+double ADXL362::GetZ() { return GetAcceleration(kAxis_Z); }
+
+double ADXL362::GetAcceleration(ADXL362::Axes axis) {
+  if (m_gsPerLSB == 0.0) return 0.0;
+
+  if (axis == kAxis_X && m_simX) return m_simX.Get();
+  if (axis == kAxis_Y && m_simY) return m_simY.Get();
+  if (axis == kAxis_Z && m_simZ) return m_simZ.Get();
+
+  uint8_t buffer[4];
+  uint8_t command[4] = {0, 0, 0, 0};
+  command[0] = kRegRead;
+  command[1] = kDataRegister + static_cast<uint8_t>(axis);
+  m_spi.Transaction(command, buffer, 4);
+
+  // Sensor is little endian... swap bytes
+  int16_t rawAccel = buffer[3] << 8 | buffer[2];
+  return rawAccel * m_gsPerLSB;
+}
+
+ADXL362::AllAxes ADXL362::GetAccelerations() {
+  AllAxes data;
+  if (m_gsPerLSB == 0.0) {
+    data.XAxis = data.YAxis = data.ZAxis = 0.0;
+    return data;
+  }
+  if (m_simX && m_simY && m_simZ) {
+    data.XAxis = m_simX.Get();
+    data.YAxis = m_simY.Get();
+    data.ZAxis = m_simZ.Get();
+    return data;
+  }
+
+  uint8_t dataBuffer[8] = {0, 0, 0, 0, 0, 0, 0, 0};
+  int16_t rawData[3];
+
+  // Select the data address.
+  dataBuffer[0] = kRegRead;
+  dataBuffer[1] = kDataRegister;
+  m_spi.Transaction(dataBuffer, dataBuffer, 8);
+
+  for (int i = 0; i < 3; i++) {
+    // Sensor is little endian... swap bytes
+    rawData[i] = dataBuffer[i * 2 + 3] << 8 | dataBuffer[i * 2 + 2];
+  }
+
+  data.XAxis = rawData[0] * m_gsPerLSB;
+  data.YAxis = rawData[1] * m_gsPerLSB;
+  data.ZAxis = rawData[2] * m_gsPerLSB;
+
+  return data;
+}
+
+void ADXL362::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("3AxisAccelerometer");
+  auto x = builder.GetEntry("X").GetHandle();
+  auto y = builder.GetEntry("Y").GetHandle();
+  auto z = builder.GetEntry("Z").GetHandle();
+  builder.SetUpdateTable([=]() {
+    auto data = GetAccelerations();
+    nt::NetworkTableEntry(x).SetDouble(data.XAxis);
+    nt::NetworkTableEntry(y).SetDouble(data.YAxis);
+    nt::NetworkTableEntry(z).SetDouble(data.ZAxis);
+  });
+}
diff --git a/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp b/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp
new file mode 100644
index 0000000..2cf2f73
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp
@@ -0,0 +1,125 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/ADXRS450_Gyro.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/DriverStation.h"
+#include "frc/Timer.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+static constexpr auto kSamplePeriod = 0.0005_s;
+static constexpr double kCalibrationSampleTime = 5.0;
+static constexpr double kDegreePerSecondPerLSB = 0.0125;
+
+// static constexpr int kRateRegister = 0x00;
+// static constexpr int kTemRegister = 0x02;
+// static constexpr int kLoCSTRegister = 0x04;
+// static constexpr int kHiCSTRegister = 0x06;
+// static constexpr int kQuadRegister = 0x08;
+// static constexpr int kFaultRegister = 0x0A;
+static constexpr int kPIDRegister = 0x0C;
+// static constexpr int kSNHighRegister = 0x0E;
+// static constexpr int kSNLowRegister = 0x10;
+
+ADXRS450_Gyro::ADXRS450_Gyro() : ADXRS450_Gyro(SPI::kOnboardCS0) {}
+
+ADXRS450_Gyro::ADXRS450_Gyro(SPI::Port port)
+    : m_spi(port), m_simDevice("ADXRS450_Gyro", port) {
+  if (m_simDevice) {
+    m_simAngle = m_simDevice.CreateDouble("Angle", false, 0.0);
+    m_simRate = m_simDevice.CreateDouble("Rate", false, 0.0);
+  }
+
+  m_spi.SetClockRate(3000000);
+  m_spi.SetMSBFirst();
+  m_spi.SetSampleDataOnLeadingEdge();
+  m_spi.SetClockActiveHigh();
+  m_spi.SetChipSelectActiveLow();
+
+  if (!m_simDevice) {
+    // Validate the part ID
+    if ((ReadRegister(kPIDRegister) & 0xff00) != 0x5200) {
+      DriverStation::ReportError("could not find ADXRS450 gyro");
+      return;
+    }
+
+    m_spi.InitAccumulator(kSamplePeriod, 0x20000000u, 4, 0x0c00000eu,
+                          0x04000000u, 10u, 16u, true, true);
+
+    Calibrate();
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_ADXRS450, port + 1);
+
+  SendableRegistry::GetInstance().AddLW(this, "ADXRS450_Gyro", port);
+}
+
+static bool CalcParity(int v) {
+  bool parity = false;
+  while (v != 0) {
+    parity = !parity;
+    v = v & (v - 1);
+  }
+  return parity;
+}
+
+static inline int BytesToIntBE(uint8_t* buf) {
+  int result = static_cast<int>(buf[0]) << 24;
+  result |= static_cast<int>(buf[1]) << 16;
+  result |= static_cast<int>(buf[2]) << 8;
+  result |= static_cast<int>(buf[3]);
+  return result;
+}
+
+uint16_t ADXRS450_Gyro::ReadRegister(int reg) {
+  int cmd = 0x80000000 | static_cast<int>(reg) << 17;
+  if (!CalcParity(cmd)) cmd |= 1u;
+
+  // big endian
+  uint8_t buf[4] = {static_cast<uint8_t>((cmd >> 24) & 0xff),
+                    static_cast<uint8_t>((cmd >> 16) & 0xff),
+                    static_cast<uint8_t>((cmd >> 8) & 0xff),
+                    static_cast<uint8_t>(cmd & 0xff)};
+
+  m_spi.Write(buf, 4);
+  m_spi.Read(false, buf, 4);
+  if ((buf[0] & 0xe0) == 0) return 0;  // error, return 0
+  return static_cast<uint16_t>((BytesToIntBE(buf) >> 5) & 0xffff);
+}
+
+double ADXRS450_Gyro::GetAngle() const {
+  if (m_simAngle) return m_simAngle.Get();
+  return m_spi.GetAccumulatorIntegratedValue() * kDegreePerSecondPerLSB;
+}
+
+double ADXRS450_Gyro::GetRate() const {
+  if (m_simRate) return m_simRate.Get();
+  return static_cast<double>(m_spi.GetAccumulatorLastValue()) *
+         kDegreePerSecondPerLSB;
+}
+
+void ADXRS450_Gyro::Reset() {
+  if (m_simAngle) m_simAngle.Set(0.0);
+  if (m_simRate) m_simRate.Set(0.0);
+  m_spi.ResetAccumulator();
+}
+
+void ADXRS450_Gyro::Calibrate() {
+  Wait(0.1);
+
+  m_spi.SetAccumulatorIntegratedCenter(0);
+  m_spi.ResetAccumulator();
+
+  Wait(kCalibrationSampleTime);
+
+  m_spi.SetAccumulatorIntegratedCenter(m_spi.GetAccumulatorIntegratedAverage());
+  m_spi.ResetAccumulator();
+}
diff --git a/wpilibc/src/main/native/cpp/AddressableLED.cpp b/wpilibc/src/main/native/cpp/AddressableLED.cpp
new file mode 100644
index 0000000..b0c3a45
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/AddressableLED.cpp
@@ -0,0 +1,129 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/AddressableLED.h"
+
+#include <hal/AddressableLED.h>
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+#include <hal/PWM.h>
+#include <hal/Ports.h>
+
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+AddressableLED::AddressableLED(int port) {
+  int32_t status = 0;
+
+  m_pwmHandle = HAL_InitializePWMPort(HAL_GetPort(port), &status);
+  wpi_setHALErrorWithRange(status, 0, HAL_GetNumPWMChannels(), port);
+  if (m_pwmHandle == HAL_kInvalidHandle) {
+    return;
+  }
+
+  m_handle = HAL_InitializeAddressableLED(m_pwmHandle, &status);
+  wpi_setHALError(status);
+  if (m_handle == HAL_kInvalidHandle) {
+    HAL_FreePWMPort(m_pwmHandle, &status);
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_AddressableLEDs, port + 1);
+}
+
+AddressableLED::~AddressableLED() {
+  HAL_FreeAddressableLED(m_handle);
+  int32_t status = 0;
+  HAL_FreePWMPort(m_pwmHandle, &status);
+}
+
+void AddressableLED::SetLength(int length) {
+  int32_t status = 0;
+  HAL_SetAddressableLEDLength(m_handle, length, &status);
+  wpi_setHALError(status);
+}
+
+static_assert(sizeof(AddressableLED::LEDData) == sizeof(HAL_AddressableLEDData),
+              "LED Structs MUST be the same size");
+
+void AddressableLED::SetData(wpi::ArrayRef<LEDData> ledData) {
+  int32_t status = 0;
+  HAL_WriteAddressableLEDData(m_handle, ledData.begin(), ledData.size(),
+                              &status);
+  wpi_setHALError(status);
+}
+
+void AddressableLED::SetData(std::initializer_list<LEDData> ledData) {
+  int32_t status = 0;
+  HAL_WriteAddressableLEDData(m_handle, ledData.begin(), ledData.size(),
+                              &status);
+  wpi_setHALError(status);
+}
+
+void AddressableLED::SetBitTiming(units::nanosecond_t lowTime0,
+                                  units::nanosecond_t highTime0,
+                                  units::nanosecond_t lowTime1,
+                                  units::nanosecond_t highTime1) {
+  int32_t status = 0;
+  HAL_SetAddressableLEDBitTiming(
+      m_handle, lowTime0.to<int32_t>(), highTime0.to<int32_t>(),
+      lowTime1.to<int32_t>(), highTime1.to<int32_t>(), &status);
+  wpi_setHALError(status);
+}
+
+void AddressableLED::SetSyncTime(units::microsecond_t syncTime) {
+  int32_t status = 0;
+  HAL_SetAddressableLEDSyncTime(m_handle, syncTime.to<int32_t>(), &status);
+  wpi_setHALError(status);
+}
+
+void AddressableLED::Start() {
+  int32_t status = 0;
+  HAL_StartAddressableLEDOutput(m_handle, &status);
+  wpi_setHALError(status);
+}
+
+void AddressableLED::Stop() {
+  int32_t status = 0;
+  HAL_StopAddressableLEDOutput(m_handle, &status);
+  wpi_setHALError(status);
+}
+
+void AddressableLED::LEDData::SetHSV(int h, int s, int v) {
+  if (s == 0) {
+    SetRGB(v, v, v);
+    return;
+  }
+
+  int region = h / 30;
+  int remainder = (h - (region * 30)) * 6;
+
+  int p = (v * (255 - s)) >> 8;
+  int q = (v * (255 - ((s * remainder) >> 8))) >> 8;
+  int t = (v * (255 - ((s * (255 - remainder)) >> 8))) >> 8;
+
+  switch (region) {
+    case 0:
+      SetRGB(v, t, p);
+      break;
+    case 1:
+      SetRGB(q, v, p);
+      break;
+    case 2:
+      SetRGB(p, v, t);
+      break;
+    case 3:
+      SetRGB(p, q, v);
+      break;
+    case 4:
+      SetRGB(t, p, v);
+      break;
+    default:
+      SetRGB(v, p, q);
+      break;
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp b/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp
new file mode 100644
index 0000000..be0c7d2
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/AnalogAccelerometer.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+AnalogAccelerometer::AnalogAccelerometer(int channel)
+    : AnalogAccelerometer(std::make_shared<AnalogInput>(channel)) {
+  SendableRegistry::GetInstance().AddChild(this, m_analogInput.get());
+}
+
+AnalogAccelerometer::AnalogAccelerometer(AnalogInput* channel)
+    : m_analogInput(channel, NullDeleter<AnalogInput>()) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitAccelerometer();
+  }
+}
+
+AnalogAccelerometer::AnalogAccelerometer(std::shared_ptr<AnalogInput> channel)
+    : m_analogInput(channel) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitAccelerometer();
+  }
+}
+
+double AnalogAccelerometer::GetAcceleration() const {
+  return (m_analogInput->GetAverageVoltage() - m_zeroGVoltage) / m_voltsPerG;
+}
+
+void AnalogAccelerometer::SetSensitivity(double sensitivity) {
+  m_voltsPerG = sensitivity;
+}
+
+void AnalogAccelerometer::SetZero(double zero) { m_zeroGVoltage = zero; }
+
+double AnalogAccelerometer::PIDGet() { return GetAcceleration(); }
+
+void AnalogAccelerometer::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Accelerometer");
+  builder.AddDoubleProperty("Value", [=]() { return GetAcceleration(); },
+                            nullptr);
+}
+
+void AnalogAccelerometer::InitAccelerometer() {
+  HAL_Report(HALUsageReporting::kResourceType_Accelerometer,
+             m_analogInput->GetChannel() + 1);
+
+  SendableRegistry::GetInstance().AddLW(this, "Accelerometer",
+                                        m_analogInput->GetChannel());
+}
diff --git a/wpilibc/src/main/native/cpp/AnalogEncoder.cpp b/wpilibc/src/main/native/cpp/AnalogEncoder.cpp
new file mode 100644
index 0000000..a194961
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/AnalogEncoder.cpp
@@ -0,0 +1,104 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/AnalogEncoder.h"
+
+#include "frc/AnalogInput.h"
+#include "frc/Counter.h"
+#include "frc/DriverStation.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+AnalogEncoder::AnalogEncoder(AnalogInput& analogInput)
+    : m_analogInput{&analogInput, NullDeleter<AnalogInput>{}},
+      m_analogTrigger{m_analogInput.get()},
+      m_counter{} {
+  Init();
+}
+
+AnalogEncoder::AnalogEncoder(AnalogInput* analogInput)
+    : m_analogInput{analogInput, NullDeleter<AnalogInput>{}},
+      m_analogTrigger{m_analogInput.get()},
+      m_counter{} {
+  Init();
+}
+
+AnalogEncoder::AnalogEncoder(std::shared_ptr<AnalogInput> analogInput)
+    : m_analogInput{std::move(analogInput)},
+      m_analogTrigger{m_analogInput.get()},
+      m_counter{} {
+  Init();
+}
+
+void AnalogEncoder::Init() {
+  m_simDevice = hal::SimDevice{"AnalogEncoder", m_analogInput->GetChannel()};
+
+  if (m_simDevice) {
+    m_simPosition = m_simDevice.CreateDouble("Position", false, 0.0);
+  }
+
+  m_analogTrigger.SetLimitsVoltage(1.25, 3.75);
+  m_counter.SetUpSource(
+      m_analogTrigger.CreateOutput(AnalogTriggerType::kRisingPulse));
+  m_counter.SetDownSource(
+      m_analogTrigger.CreateOutput(AnalogTriggerType::kFallingPulse));
+
+  SendableRegistry::GetInstance().AddLW(this, "DutyCycle Encoder",
+                                        m_analogInput->GetChannel());
+}
+
+units::turn_t AnalogEncoder::Get() const {
+  if (m_simPosition) return units::turn_t{m_simPosition.Get()};
+
+  // As the values are not atomic, keep trying until we get 2 reads of the same
+  // value If we don't within 10 attempts, error
+  for (int i = 0; i < 10; i++) {
+    auto counter = m_counter.Get();
+    auto pos = m_analogInput->GetVoltage();
+    auto counter2 = m_counter.Get();
+    auto pos2 = m_analogInput->GetVoltage();
+    if (counter == counter2 && pos == pos2) {
+      units::turn_t turns{counter + pos - m_positionOffset};
+      m_lastPosition = turns;
+      return turns;
+    }
+  }
+
+  frc::DriverStation::GetInstance().ReportWarning(
+      "Failed to read Analog Encoder. Potential Speed Overrun. Returning last "
+      "value");
+  return m_lastPosition;
+}
+
+double AnalogEncoder::GetPositionOffset() const { return m_positionOffset; }
+
+void AnalogEncoder::SetDistancePerRotation(double distancePerRotation) {
+  m_distancePerRotation = distancePerRotation;
+}
+
+double AnalogEncoder::GetDistancePerRotation() const {
+  return m_distancePerRotation;
+}
+
+double AnalogEncoder::GetDistance() const {
+  return Get().to<double>() * GetDistancePerRotation();
+}
+
+void AnalogEncoder::Reset() {
+  m_counter.Reset();
+  m_positionOffset = m_analogInput->GetVoltage();
+}
+
+void AnalogEncoder::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("AbsoluteEncoder");
+  builder.AddDoubleProperty("Distance", [this] { return this->GetDistance(); },
+                            nullptr);
+  builder.AddDoubleProperty("Distance Per Rotation",
+                            [this] { return this->GetDistancePerRotation(); },
+                            nullptr);
+}
diff --git a/wpilibc/src/main/native/cpp/AnalogGyro.cpp b/wpilibc/src/main/native/cpp/AnalogGyro.cpp
new file mode 100644
index 0000000..c891506
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/AnalogGyro.cpp
@@ -0,0 +1,162 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/AnalogGyro.h"
+
+#include <climits>
+#include <utility>
+
+#include <hal/AnalogGyro.h>
+#include <hal/Errors.h>
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/AnalogInput.h"
+#include "frc/Timer.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+AnalogGyro::AnalogGyro(int channel)
+    : AnalogGyro(std::make_shared<AnalogInput>(channel)) {
+  SendableRegistry::GetInstance().AddChild(this, m_analog.get());
+}
+
+AnalogGyro::AnalogGyro(AnalogInput* channel)
+    : AnalogGyro(
+          std::shared_ptr<AnalogInput>(channel, NullDeleter<AnalogInput>())) {}
+
+AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel)
+    : m_analog(channel) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitGyro();
+    Calibrate();
+  }
+}
+
+AnalogGyro::AnalogGyro(int channel, int center, double offset)
+    : AnalogGyro(std::make_shared<AnalogInput>(channel), center, offset) {
+  SendableRegistry::GetInstance().AddChild(this, m_analog.get());
+}
+
+AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel, int center,
+                       double offset)
+    : m_analog(channel) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitGyro();
+    int32_t status = 0;
+    HAL_SetAnalogGyroParameters(m_gyroHandle, kDefaultVoltsPerDegreePerSecond,
+                                offset, center, &status);
+    if (status != 0) {
+      wpi_setHALError(status);
+      m_gyroHandle = HAL_kInvalidHandle;
+      return;
+    }
+    Reset();
+  }
+}
+
+AnalogGyro::~AnalogGyro() { HAL_FreeAnalogGyro(m_gyroHandle); }
+
+double AnalogGyro::GetAngle() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetAnalogGyroAngle(m_gyroHandle, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+double AnalogGyro::GetRate() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetAnalogGyroRate(m_gyroHandle, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+int AnalogGyro::GetCenter() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetAnalogGyroCenter(m_gyroHandle, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+double AnalogGyro::GetOffset() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetAnalogGyroOffset(m_gyroHandle, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+void AnalogGyro::SetSensitivity(double voltsPerDegreePerSecond) {
+  int32_t status = 0;
+  HAL_SetAnalogGyroVoltsPerDegreePerSecond(m_gyroHandle,
+                                           voltsPerDegreePerSecond, &status);
+  wpi_setHALError(status);
+}
+
+void AnalogGyro::SetDeadband(double volts) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogGyroDeadband(m_gyroHandle, volts, &status);
+  wpi_setHALError(status);
+}
+
+void AnalogGyro::Reset() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_ResetAnalogGyro(m_gyroHandle, &status);
+  wpi_setHALError(status);
+}
+
+void AnalogGyro::InitGyro() {
+  if (StatusIsFatal()) return;
+  if (m_gyroHandle == HAL_kInvalidHandle) {
+    int32_t status = 0;
+    m_gyroHandle = HAL_InitializeAnalogGyro(m_analog->m_port, &status);
+    if (status == PARAMETER_OUT_OF_RANGE) {
+      wpi_setWPIErrorWithContext(ParameterOutOfRange,
+                                 " channel (must be accumulator channel)");
+      m_analog = nullptr;
+      m_gyroHandle = HAL_kInvalidHandle;
+      return;
+    }
+    if (status != 0) {
+      wpi_setHALError(status);
+      m_analog = nullptr;
+      m_gyroHandle = HAL_kInvalidHandle;
+      return;
+    }
+  }
+
+  int32_t status = 0;
+  HAL_SetupAnalogGyro(m_gyroHandle, &status);
+  if (status != 0) {
+    wpi_setHALError(status);
+    m_analog = nullptr;
+    m_gyroHandle = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel() + 1);
+
+  SendableRegistry::GetInstance().AddLW(this, "AnalogGyro",
+                                        m_analog->GetChannel());
+}
+
+void AnalogGyro::Calibrate() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_CalibrateAnalogGyro(m_gyroHandle, &status);
+  wpi_setHALError(status);
+}
diff --git a/wpilibc/src/main/native/cpp/AnalogInput.cpp b/wpilibc/src/main/native/cpp/AnalogInput.cpp
new file mode 100644
index 0000000..c8197b7
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/AnalogInput.cpp
@@ -0,0 +1,235 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/AnalogInput.h"
+
+#include <utility>
+
+#include <hal/AnalogAccumulator.h>
+#include <hal/AnalogInput.h>
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+#include <hal/Ports.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/Timer.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+AnalogInput::AnalogInput(int channel) {
+  if (!SensorUtil::CheckAnalogInputChannel(channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
+                               "Analog Input " + wpi::Twine(channel));
+    return;
+  }
+
+  m_channel = channel;
+
+  HAL_PortHandle port = HAL_GetPort(channel);
+  int32_t status = 0;
+  m_port = HAL_InitializeAnalogInputPort(port, &status);
+  if (status != 0) {
+    wpi_setHALErrorWithRange(status, 0, HAL_GetNumAnalogInputs(), channel);
+    m_channel = std::numeric_limits<int>::max();
+    m_port = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_AnalogChannel, channel + 1);
+
+  SendableRegistry::GetInstance().AddLW(this, "AnalogInput", channel);
+}
+
+AnalogInput::~AnalogInput() { HAL_FreeAnalogInputPort(m_port); }
+
+int AnalogInput::GetValue() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetAnalogValue(m_port, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+int AnalogInput::GetAverageValue() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetAnalogAverageValue(m_port, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+double AnalogInput::GetVoltage() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double voltage = HAL_GetAnalogVoltage(m_port, &status);
+  wpi_setHALError(status);
+  return voltage;
+}
+
+double AnalogInput::GetAverageVoltage() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double voltage = HAL_GetAnalogAverageVoltage(m_port, &status);
+  wpi_setHALError(status);
+  return voltage;
+}
+
+int AnalogInput::GetChannel() const {
+  if (StatusIsFatal()) return 0;
+  return m_channel;
+}
+
+void AnalogInput::SetAverageBits(int bits) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogAverageBits(m_port, bits, &status);
+  wpi_setHALError(status);
+}
+
+int AnalogInput::GetAverageBits() const {
+  int32_t status = 0;
+  int averageBits = HAL_GetAnalogAverageBits(m_port, &status);
+  wpi_setHALError(status);
+  return averageBits;
+}
+
+void AnalogInput::SetOversampleBits(int bits) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogOversampleBits(m_port, bits, &status);
+  wpi_setHALError(status);
+}
+
+int AnalogInput::GetOversampleBits() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int oversampleBits = HAL_GetAnalogOversampleBits(m_port, &status);
+  wpi_setHALError(status);
+  return oversampleBits;
+}
+
+int AnalogInput::GetLSBWeight() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int lsbWeight = HAL_GetAnalogLSBWeight(m_port, &status);
+  wpi_setHALError(status);
+  return lsbWeight;
+}
+
+int AnalogInput::GetOffset() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int offset = HAL_GetAnalogOffset(m_port, &status);
+  wpi_setHALError(status);
+  return offset;
+}
+
+bool AnalogInput::IsAccumulatorChannel() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool isAccum = HAL_IsAccumulatorChannel(m_port, &status);
+  wpi_setHALError(status);
+  return isAccum;
+}
+
+void AnalogInput::InitAccumulator() {
+  if (StatusIsFatal()) return;
+  m_accumulatorOffset = 0;
+  int32_t status = 0;
+  HAL_InitAccumulator(m_port, &status);
+  wpi_setHALError(status);
+}
+
+void AnalogInput::SetAccumulatorInitialValue(int64_t initialValue) {
+  if (StatusIsFatal()) return;
+  m_accumulatorOffset = initialValue;
+}
+
+void AnalogInput::ResetAccumulator() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_ResetAccumulator(m_port, &status);
+  wpi_setHALError(status);
+
+  if (!StatusIsFatal()) {
+    // Wait until the next sample, so the next call to GetAccumulator*()
+    // won't have old values.
+    const double sampleTime = 1.0 / GetSampleRate();
+    const double overSamples = 1 << GetOversampleBits();
+    const double averageSamples = 1 << GetAverageBits();
+    Wait(sampleTime * overSamples * averageSamples);
+  }
+}
+
+void AnalogInput::SetAccumulatorCenter(int center) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAccumulatorCenter(m_port, center, &status);
+  wpi_setHALError(status);
+}
+
+void AnalogInput::SetAccumulatorDeadband(int deadband) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAccumulatorDeadband(m_port, deadband, &status);
+  wpi_setHALError(status);
+}
+
+int64_t AnalogInput::GetAccumulatorValue() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int64_t value = HAL_GetAccumulatorValue(m_port, &status);
+  wpi_setHALError(status);
+  return value + m_accumulatorOffset;
+}
+
+int64_t AnalogInput::GetAccumulatorCount() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int64_t count = HAL_GetAccumulatorCount(m_port, &status);
+  wpi_setHALError(status);
+  return count;
+}
+
+void AnalogInput::GetAccumulatorOutput(int64_t& value, int64_t& count) const {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_GetAccumulatorOutput(m_port, &value, &count, &status);
+  wpi_setHALError(status);
+  value += m_accumulatorOffset;
+}
+
+void AnalogInput::SetSampleRate(double samplesPerSecond) {
+  int32_t status = 0;
+  HAL_SetAnalogSampleRate(samplesPerSecond, &status);
+  wpi_setGlobalHALError(status);
+}
+
+double AnalogInput::GetSampleRate() {
+  int32_t status = 0;
+  double sampleRate = HAL_GetAnalogSampleRate(&status);
+  wpi_setGlobalHALError(status);
+  return sampleRate;
+}
+
+double AnalogInput::PIDGet() {
+  if (StatusIsFatal()) return 0.0;
+  return GetAverageVoltage();
+}
+
+void AnalogInput::SetSimDevice(HAL_SimDeviceHandle device) {
+  HAL_SetAnalogInputSimDevice(m_port, device);
+}
+
+void AnalogInput::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Analog Input");
+  builder.AddDoubleProperty("Value", [=]() { return GetAverageVoltage(); },
+                            nullptr);
+}
diff --git a/wpilibc/src/main/native/cpp/AnalogOutput.cpp b/wpilibc/src/main/native/cpp/AnalogOutput.cpp
new file mode 100644
index 0000000..041b446
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/AnalogOutput.cpp
@@ -0,0 +1,74 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/AnalogOutput.h"
+
+#include <limits>
+#include <utility>
+
+#include <hal/AnalogOutput.h>
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+#include <hal/Ports.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+AnalogOutput::AnalogOutput(int channel) {
+  if (!SensorUtil::CheckAnalogOutputChannel(channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
+                               "analog output " + wpi::Twine(channel));
+    m_channel = std::numeric_limits<int>::max();
+    m_port = HAL_kInvalidHandle;
+    return;
+  }
+
+  m_channel = channel;
+
+  HAL_PortHandle port = HAL_GetPort(m_channel);
+  int32_t status = 0;
+  m_port = HAL_InitializeAnalogOutputPort(port, &status);
+  if (status != 0) {
+    wpi_setHALErrorWithRange(status, 0, HAL_GetNumAnalogOutputs(), channel);
+    m_channel = std::numeric_limits<int>::max();
+    m_port = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_AnalogOutput, m_channel + 1);
+  SendableRegistry::GetInstance().AddLW(this, "AnalogOutput", m_channel);
+}
+
+AnalogOutput::~AnalogOutput() { HAL_FreeAnalogOutputPort(m_port); }
+
+void AnalogOutput::SetVoltage(double voltage) {
+  int32_t status = 0;
+  HAL_SetAnalogOutput(m_port, voltage, &status);
+
+  wpi_setHALError(status);
+}
+
+double AnalogOutput::GetVoltage() const {
+  int32_t status = 0;
+  double voltage = HAL_GetAnalogOutput(m_port, &status);
+
+  wpi_setHALError(status);
+
+  return voltage;
+}
+
+int AnalogOutput::GetChannel() { return m_channel; }
+
+void AnalogOutput::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Analog Output");
+  builder.AddDoubleProperty("Value", [=]() { return GetVoltage(); },
+                            [=](double value) { SetVoltage(value); });
+}
diff --git a/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp b/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp
new file mode 100644
index 0000000..b650ec7
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/AnalogPotentiometer.h"
+
+#include "frc/RobotController.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+AnalogPotentiometer::AnalogPotentiometer(int channel, double fullRange,
+                                         double offset)
+    : AnalogPotentiometer(std::make_shared<AnalogInput>(channel), fullRange,
+                          offset) {
+  SendableRegistry::GetInstance().AddChild(this, m_analog_input.get());
+}
+
+AnalogPotentiometer::AnalogPotentiometer(AnalogInput* input, double fullRange,
+                                         double offset)
+    : AnalogPotentiometer(
+          std::shared_ptr<AnalogInput>(input, NullDeleter<AnalogInput>()),
+          fullRange, offset) {}
+
+AnalogPotentiometer::AnalogPotentiometer(std::shared_ptr<AnalogInput> input,
+                                         double fullRange, double offset)
+    : m_analog_input(input), m_fullRange(fullRange), m_offset(offset) {
+  SendableRegistry::GetInstance().AddLW(this, "AnalogPotentiometer",
+                                        m_analog_input->GetChannel());
+}
+
+double AnalogPotentiometer::Get() const {
+  return (m_analog_input->GetVoltage() / RobotController::GetVoltage5V()) *
+             m_fullRange +
+         m_offset;
+}
+
+double AnalogPotentiometer::PIDGet() { return Get(); }
+
+void AnalogPotentiometer::InitSendable(SendableBuilder& builder) {
+  m_analog_input->InitSendable(builder);
+}
diff --git a/wpilibc/src/main/native/cpp/AnalogTrigger.cpp b/wpilibc/src/main/native/cpp/AnalogTrigger.cpp
new file mode 100644
index 0000000..ddbb7c8
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/AnalogTrigger.cpp
@@ -0,0 +1,155 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/AnalogTrigger.h"
+
+#include <utility>
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/AnalogInput.h"
+#include "frc/DutyCycle.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+AnalogTrigger::AnalogTrigger(int channel)
+    : AnalogTrigger(new AnalogInput(channel)) {
+  m_ownsAnalog = true;
+  SendableRegistry::GetInstance().AddChild(this, m_analogInput);
+}
+
+AnalogTrigger::AnalogTrigger(AnalogInput* input) {
+  m_analogInput = input;
+  int32_t status = 0;
+  m_trigger = HAL_InitializeAnalogTrigger(input->m_port, &status);
+  if (status != 0) {
+    wpi_setHALError(status);
+    m_trigger = HAL_kInvalidHandle;
+    return;
+  }
+  int index = GetIndex();
+
+  HAL_Report(HALUsageReporting::kResourceType_AnalogTrigger, index + 1);
+  SendableRegistry::GetInstance().AddLW(this, "AnalogTrigger", index);
+}
+
+AnalogTrigger::AnalogTrigger(DutyCycle* input) {
+  m_dutyCycle = input;
+  int32_t status = 0;
+  m_trigger = HAL_InitializeAnalogTriggerDutyCycle(input->m_handle, &status);
+  if (status != 0) {
+    wpi_setHALError(status);
+    m_trigger = HAL_kInvalidHandle;
+    return;
+  }
+  int index = GetIndex();
+
+  HAL_Report(HALUsageReporting::kResourceType_AnalogTrigger, index + 1);
+  SendableRegistry::GetInstance().AddLW(this, "AnalogTrigger", index);
+}
+
+AnalogTrigger::~AnalogTrigger() {
+  int32_t status = 0;
+  HAL_CleanAnalogTrigger(m_trigger, &status);
+
+  if (m_ownsAnalog) {
+    delete m_analogInput;
+  }
+}
+
+AnalogTrigger::AnalogTrigger(AnalogTrigger&& rhs)
+    : ErrorBase(std::move(rhs)),
+      SendableHelper(std::move(rhs)),
+      m_trigger(std::move(rhs.m_trigger)) {
+  std::swap(m_analogInput, rhs.m_analogInput);
+  std::swap(m_dutyCycle, rhs.m_dutyCycle);
+  std::swap(m_ownsAnalog, rhs.m_ownsAnalog);
+}
+
+AnalogTrigger& AnalogTrigger::operator=(AnalogTrigger&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+  SendableHelper::operator=(std::move(rhs));
+
+  m_trigger = std::move(rhs.m_trigger);
+  std::swap(m_analogInput, rhs.m_analogInput);
+  std::swap(m_dutyCycle, rhs.m_dutyCycle);
+  std::swap(m_ownsAnalog, rhs.m_ownsAnalog);
+
+  return *this;
+}
+
+void AnalogTrigger::SetLimitsVoltage(double lower, double upper) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerLimitsVoltage(m_trigger, lower, upper, &status);
+  wpi_setHALError(status);
+}
+
+void AnalogTrigger::SetLimitsDutyCycle(double lower, double upper) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerLimitsDutyCycle(m_trigger, lower, upper, &status);
+  wpi_setHALError(status);
+}
+
+void AnalogTrigger::SetLimitsRaw(int lower, int upper) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerLimitsRaw(m_trigger, lower, upper, &status);
+  wpi_setHALError(status);
+}
+
+void AnalogTrigger::SetAveraged(bool useAveragedValue) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerAveraged(m_trigger, useAveragedValue, &status);
+  wpi_setHALError(status);
+}
+
+void AnalogTrigger::SetFiltered(bool useFilteredValue) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerFiltered(m_trigger, useFilteredValue, &status);
+  wpi_setHALError(status);
+}
+
+int AnalogTrigger::GetIndex() const {
+  if (StatusIsFatal()) return -1;
+  int32_t status = 0;
+  auto ret = HAL_GetAnalogTriggerFPGAIndex(m_trigger, &status);
+  wpi_setHALError(status);
+  return ret;
+}
+
+bool AnalogTrigger::GetInWindow() {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool result = HAL_GetAnalogTriggerInWindow(m_trigger, &status);
+  wpi_setHALError(status);
+  return result;
+}
+
+bool AnalogTrigger::GetTriggerState() {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool result = HAL_GetAnalogTriggerTriggerState(m_trigger, &status);
+  wpi_setHALError(status);
+  return result;
+}
+
+std::shared_ptr<AnalogTriggerOutput> AnalogTrigger::CreateOutput(
+    AnalogTriggerType type) const {
+  if (StatusIsFatal()) return nullptr;
+  return std::shared_ptr<AnalogTriggerOutput>(
+      new AnalogTriggerOutput(*this, type), NullDeleter<AnalogTriggerOutput>());
+}
+
+void AnalogTrigger::InitSendable(SendableBuilder& builder) {
+  if (m_ownsAnalog) m_analogInput->InitSendable(builder);
+}
diff --git a/wpilibc/src/main/native/cpp/AnalogTriggerOutput.cpp b/wpilibc/src/main/native/cpp/AnalogTriggerOutput.cpp
new file mode 100644
index 0000000..8fba479
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/AnalogTriggerOutput.cpp
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/AnalogTriggerOutput.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/AnalogTrigger.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+bool AnalogTriggerOutput::Get() const {
+  int32_t status = 0;
+  bool result = HAL_GetAnalogTriggerOutput(
+      m_trigger->m_trigger, static_cast<HAL_AnalogTriggerType>(m_outputType),
+      &status);
+  wpi_setHALError(status);
+  return result;
+}
+
+HAL_Handle AnalogTriggerOutput::GetPortHandleForRouting() const {
+  return m_trigger->m_trigger;
+}
+
+AnalogTriggerType AnalogTriggerOutput::GetAnalogTriggerTypeForRouting() const {
+  return m_outputType;
+}
+
+bool AnalogTriggerOutput::IsAnalogTrigger() const { return true; }
+
+int AnalogTriggerOutput::GetChannel() const { return m_trigger->GetIndex(); }
+
+void AnalogTriggerOutput::InitSendable(SendableBuilder&) {}
+
+AnalogTriggerOutput::AnalogTriggerOutput(const AnalogTrigger& trigger,
+                                         AnalogTriggerType outputType)
+    : m_trigger(&trigger), m_outputType(outputType) {
+  HAL_Report(HALUsageReporting::kResourceType_AnalogTriggerOutput,
+             trigger.GetIndex() + 1, static_cast<uint8_t>(outputType) + 1);
+}
diff --git a/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp b/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp
new file mode 100644
index 0000000..d7cdef6
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/BuiltInAccelerometer.h"
+
+#include <hal/Accelerometer.h>
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+BuiltInAccelerometer::BuiltInAccelerometer(Range range) {
+  SetRange(range);
+
+  HAL_Report(HALUsageReporting::kResourceType_Accelerometer, 0, 0,
+             "Built-in accelerometer");
+  SendableRegistry::GetInstance().AddLW(this, "BuiltInAccel");
+}
+
+void BuiltInAccelerometer::SetRange(Range range) {
+  if (range == kRange_16G) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange, "16G range not supported (use k2G, k4G, or k8G)");
+  }
+
+  HAL_SetAccelerometerActive(false);
+  HAL_SetAccelerometerRange((HAL_AccelerometerRange)range);
+  HAL_SetAccelerometerActive(true);
+}
+
+double BuiltInAccelerometer::GetX() { return HAL_GetAccelerometerX(); }
+
+double BuiltInAccelerometer::GetY() { return HAL_GetAccelerometerY(); }
+
+double BuiltInAccelerometer::GetZ() { return HAL_GetAccelerometerZ(); }
+
+void BuiltInAccelerometer::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("3AxisAccelerometer");
+  builder.AddDoubleProperty("X", [=]() { return GetX(); }, nullptr);
+  builder.AddDoubleProperty("Y", [=]() { return GetY(); }, nullptr);
+  builder.AddDoubleProperty("Z", [=]() { return GetZ(); }, nullptr);
+}
diff --git a/wpilibc/src/main/native/cpp/CAN.cpp b/wpilibc/src/main/native/cpp/CAN.cpp
new file mode 100644
index 0000000..797b9ff
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/CAN.cpp
@@ -0,0 +1,123 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/CAN.h"
+
+#include <utility>
+
+#include <hal/CAN.h>
+#include <hal/CANAPI.h>
+#include <hal/Errors.h>
+#include <hal/FRCUsageReporting.h>
+
+using namespace frc;
+
+CAN::CAN(int deviceId) {
+  int32_t status = 0;
+  m_handle =
+      HAL_InitializeCAN(kTeamManufacturer, deviceId, kTeamDeviceType, &status);
+  if (status != 0) {
+    wpi_setHALError(status);
+    m_handle = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_CAN, deviceId + 1);
+}
+
+CAN::CAN(int deviceId, int deviceManufacturer, int deviceType) {
+  int32_t status = 0;
+  m_handle = HAL_InitializeCAN(
+      static_cast<HAL_CANManufacturer>(deviceManufacturer), deviceId,
+      static_cast<HAL_CANDeviceType>(deviceType), &status);
+  if (status != 0) {
+    wpi_setHALError(status);
+    m_handle = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_CAN, deviceId + 1);
+}
+
+CAN::~CAN() {
+  if (StatusIsFatal()) return;
+  if (m_handle != HAL_kInvalidHandle) {
+    HAL_CleanCAN(m_handle);
+    m_handle = HAL_kInvalidHandle;
+  }
+}
+
+void CAN::WritePacket(const uint8_t* data, int length, int apiId) {
+  int32_t status = 0;
+  HAL_WriteCANPacket(m_handle, data, length, apiId, &status);
+  wpi_setHALError(status);
+}
+
+void CAN::WritePacketRepeating(const uint8_t* data, int length, int apiId,
+                               int repeatMs) {
+  int32_t status = 0;
+  HAL_WriteCANPacketRepeating(m_handle, data, length, apiId, repeatMs, &status);
+  wpi_setHALError(status);
+}
+
+void CAN::WriteRTRFrame(int length, int apiId) {
+  int32_t status = 0;
+  HAL_WriteCANRTRFrame(m_handle, length, apiId, &status);
+  wpi_setHALError(status);
+}
+
+void CAN::StopPacketRepeating(int apiId) {
+  int32_t status = 0;
+  HAL_StopCANPacketRepeating(m_handle, apiId, &status);
+  wpi_setHALError(status);
+}
+
+bool CAN::ReadPacketNew(int apiId, CANData* data) {
+  int32_t status = 0;
+  HAL_ReadCANPacketNew(m_handle, apiId, data->data, &data->length,
+                       &data->timestamp, &status);
+  if (status == HAL_ERR_CANSessionMux_MessageNotFound) {
+    return false;
+  }
+  if (status != 0) {
+    wpi_setHALError(status);
+    return false;
+  } else {
+    return true;
+  }
+}
+
+bool CAN::ReadPacketLatest(int apiId, CANData* data) {
+  int32_t status = 0;
+  HAL_ReadCANPacketLatest(m_handle, apiId, data->data, &data->length,
+                          &data->timestamp, &status);
+  if (status == HAL_ERR_CANSessionMux_MessageNotFound) {
+    return false;
+  }
+  if (status != 0) {
+    wpi_setHALError(status);
+    return false;
+  } else {
+    return true;
+  }
+}
+
+bool CAN::ReadPacketTimeout(int apiId, int timeoutMs, CANData* data) {
+  int32_t status = 0;
+  HAL_ReadCANPacketTimeout(m_handle, apiId, data->data, &data->length,
+                           &data->timestamp, timeoutMs, &status);
+  if (status == HAL_CAN_TIMEOUT ||
+      status == HAL_ERR_CANSessionMux_MessageNotFound) {
+    return false;
+  }
+  if (status != 0) {
+    wpi_setHALError(status);
+    return false;
+  } else {
+    return true;
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/Compressor.cpp b/wpilibc/src/main/native/cpp/Compressor.cpp
new file mode 100644
index 0000000..29789be
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Compressor.cpp
@@ -0,0 +1,218 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Compressor.h"
+
+#include <hal/Compressor.h>
+#include <hal/FRCUsageReporting.h>
+#include <hal/Ports.h>
+#include <hal/Solenoid.h>
+
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+Compressor::Compressor(int pcmID) : m_module(pcmID) {
+  int32_t status = 0;
+  m_compressorHandle = HAL_InitializeCompressor(m_module, &status);
+  if (status != 0) {
+    wpi_setHALErrorWithRange(status, 0, HAL_GetNumPCMModules(), pcmID);
+    return;
+  }
+  SetClosedLoopControl(true);
+
+  HAL_Report(HALUsageReporting::kResourceType_Compressor, pcmID + 1);
+  SendableRegistry::GetInstance().AddLW(this, "Compressor", pcmID);
+}
+
+void Compressor::Start() {
+  if (StatusIsFatal()) return;
+  SetClosedLoopControl(true);
+}
+
+void Compressor::Stop() {
+  if (StatusIsFatal()) return;
+  SetClosedLoopControl(false);
+}
+
+bool Compressor::Enabled() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressor(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+bool Compressor::GetPressureSwitchValue() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorPressureSwitch(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+double Compressor::GetCompressorCurrent() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  double value;
+
+  value = HAL_GetCompressorCurrent(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+void Compressor::SetClosedLoopControl(bool on) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+
+  HAL_SetCompressorClosedLoopControl(m_compressorHandle, on, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+}
+
+bool Compressor::GetClosedLoopControl() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorClosedLoopControl(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+bool Compressor::GetCompressorCurrentTooHighFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorCurrentTooHighFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+bool Compressor::GetCompressorCurrentTooHighStickyFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value =
+      HAL_GetCompressorCurrentTooHighStickyFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+bool Compressor::GetCompressorShortedStickyFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorShortedStickyFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+bool Compressor::GetCompressorShortedFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorShortedFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+bool Compressor::GetCompressorNotConnectedStickyFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorNotConnectedStickyFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+bool Compressor::GetCompressorNotConnectedFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorNotConnectedFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+void Compressor::ClearAllPCMStickyFaults() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+
+  HAL_ClearAllPCMStickyFaults(m_module, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+}
+
+void Compressor::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Compressor");
+  builder.AddBooleanProperty("Enabled", [=]() { return Enabled(); },
+                             [=](bool value) {
+                               if (value)
+                                 Start();
+                               else
+                                 Stop();
+                             });
+  builder.AddBooleanProperty(
+      "Pressure switch", [=]() { return GetPressureSwitchValue(); }, nullptr);
+}
diff --git a/wpilibc/src/main/native/cpp/Counter.cpp b/wpilibc/src/main/native/cpp/Counter.cpp
new file mode 100644
index 0000000..d2158ca
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Counter.cpp
@@ -0,0 +1,336 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Counter.h"
+
+#include <utility>
+
+#include <hal/Counter.h>
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/AnalogTrigger.h"
+#include "frc/DigitalInput.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+Counter::Counter(Mode mode) {
+  int32_t status = 0;
+  m_counter = HAL_InitializeCounter((HAL_Counter_Mode)mode, &m_index, &status);
+  wpi_setHALError(status);
+
+  SetMaxPeriod(0.5);
+
+  HAL_Report(HALUsageReporting::kResourceType_Counter, m_index + 1, mode + 1);
+  SendableRegistry::GetInstance().AddLW(this, "Counter", m_index);
+}
+
+Counter::Counter(int channel) : Counter(kTwoPulse) {
+  SetUpSource(channel);
+  ClearDownSource();
+}
+
+Counter::Counter(DigitalSource* source) : Counter(kTwoPulse) {
+  SetUpSource(source);
+  ClearDownSource();
+}
+
+Counter::Counter(std::shared_ptr<DigitalSource> source) : Counter(kTwoPulse) {
+  SetUpSource(source);
+  ClearDownSource();
+}
+
+Counter::Counter(const AnalogTrigger& trigger) : Counter(kTwoPulse) {
+  SetUpSource(trigger.CreateOutput(AnalogTriggerType::kState));
+  ClearDownSource();
+}
+
+Counter::Counter(EncodingType encodingType, DigitalSource* upSource,
+                 DigitalSource* downSource, bool inverted)
+    : Counter(encodingType,
+              std::shared_ptr<DigitalSource>(upSource,
+                                             NullDeleter<DigitalSource>()),
+              std::shared_ptr<DigitalSource>(downSource,
+                                             NullDeleter<DigitalSource>()),
+              inverted) {}
+
+Counter::Counter(EncodingType encodingType,
+                 std::shared_ptr<DigitalSource> upSource,
+                 std::shared_ptr<DigitalSource> downSource, bool inverted)
+    : Counter(kExternalDirection) {
+  if (encodingType != k1X && encodingType != k2X) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange,
+        "Counter only supports 1X and 2X quadrature decoding.");
+    return;
+  }
+  SetUpSource(upSource);
+  SetDownSource(downSource);
+  int32_t status = 0;
+
+  if (encodingType == k1X) {
+    SetUpSourceEdge(true, false);
+    HAL_SetCounterAverageSize(m_counter, 1, &status);
+  } else {
+    SetUpSourceEdge(true, true);
+    HAL_SetCounterAverageSize(m_counter, 2, &status);
+  }
+
+  wpi_setHALError(status);
+  SetDownSourceEdge(inverted, true);
+}
+
+Counter::~Counter() {
+  SetUpdateWhenEmpty(true);
+
+  int32_t status = 0;
+  HAL_FreeCounter(m_counter, &status);
+  wpi_setHALError(status);
+}
+
+void Counter::SetUpSource(int channel) {
+  if (StatusIsFatal()) return;
+  SetUpSource(std::make_shared<DigitalInput>(channel));
+  SendableRegistry::GetInstance().AddChild(this, m_upSource.get());
+}
+
+void Counter::SetUpSource(AnalogTrigger* analogTrigger,
+                          AnalogTriggerType triggerType) {
+  SetUpSource(std::shared_ptr<AnalogTrigger>(analogTrigger,
+                                             NullDeleter<AnalogTrigger>()),
+              triggerType);
+}
+
+void Counter::SetUpSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                          AnalogTriggerType triggerType) {
+  if (StatusIsFatal()) return;
+  SetUpSource(analogTrigger->CreateOutput(triggerType));
+}
+
+void Counter::SetUpSource(DigitalSource* source) {
+  SetUpSource(
+      std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>()));
+}
+
+void Counter::SetUpSource(std::shared_ptr<DigitalSource> source) {
+  if (StatusIsFatal()) return;
+  m_upSource = source;
+  if (m_upSource->StatusIsFatal()) {
+    CloneError(*m_upSource);
+  } else {
+    int32_t status = 0;
+    HAL_SetCounterUpSource(
+        m_counter, source->GetPortHandleForRouting(),
+        (HAL_AnalogTriggerType)source->GetAnalogTriggerTypeForRouting(),
+        &status);
+    wpi_setHALError(status);
+  }
+}
+
+void Counter::SetUpSource(DigitalSource& source) {
+  SetUpSource(
+      std::shared_ptr<DigitalSource>(&source, NullDeleter<DigitalSource>()));
+}
+
+void Counter::SetUpSourceEdge(bool risingEdge, bool fallingEdge) {
+  if (StatusIsFatal()) return;
+  if (m_upSource == nullptr) {
+    wpi_setWPIErrorWithContext(
+        NullParameter,
+        "Must set non-nullptr UpSource before setting UpSourceEdge");
+  }
+  int32_t status = 0;
+  HAL_SetCounterUpSourceEdge(m_counter, risingEdge, fallingEdge, &status);
+  wpi_setHALError(status);
+}
+
+void Counter::ClearUpSource() {
+  if (StatusIsFatal()) return;
+  m_upSource.reset();
+  int32_t status = 0;
+  HAL_ClearCounterUpSource(m_counter, &status);
+  wpi_setHALError(status);
+}
+
+void Counter::SetDownSource(int channel) {
+  if (StatusIsFatal()) return;
+  SetDownSource(std::make_shared<DigitalInput>(channel));
+  SendableRegistry::GetInstance().AddChild(this, m_downSource.get());
+}
+
+void Counter::SetDownSource(AnalogTrigger* analogTrigger,
+                            AnalogTriggerType triggerType) {
+  SetDownSource(std::shared_ptr<AnalogTrigger>(analogTrigger,
+                                               NullDeleter<AnalogTrigger>()),
+                triggerType);
+}
+
+void Counter::SetDownSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                            AnalogTriggerType triggerType) {
+  if (StatusIsFatal()) return;
+  SetDownSource(analogTrigger->CreateOutput(triggerType));
+}
+
+void Counter::SetDownSource(DigitalSource* source) {
+  SetDownSource(
+      std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>()));
+}
+
+void Counter::SetDownSource(DigitalSource& source) {
+  SetDownSource(
+      std::shared_ptr<DigitalSource>(&source, NullDeleter<DigitalSource>()));
+}
+
+void Counter::SetDownSource(std::shared_ptr<DigitalSource> source) {
+  if (StatusIsFatal()) return;
+  m_downSource = source;
+  if (m_downSource->StatusIsFatal()) {
+    CloneError(*m_downSource);
+  } else {
+    int32_t status = 0;
+    HAL_SetCounterDownSource(
+        m_counter, source->GetPortHandleForRouting(),
+        (HAL_AnalogTriggerType)source->GetAnalogTriggerTypeForRouting(),
+        &status);
+    wpi_setHALError(status);
+  }
+}
+
+void Counter::SetDownSourceEdge(bool risingEdge, bool fallingEdge) {
+  if (StatusIsFatal()) return;
+  if (m_downSource == nullptr) {
+    wpi_setWPIErrorWithContext(
+        NullParameter,
+        "Must set non-nullptr DownSource before setting DownSourceEdge");
+  }
+  int32_t status = 0;
+  HAL_SetCounterDownSourceEdge(m_counter, risingEdge, fallingEdge, &status);
+  wpi_setHALError(status);
+}
+
+void Counter::ClearDownSource() {
+  if (StatusIsFatal()) return;
+  m_downSource.reset();
+  int32_t status = 0;
+  HAL_ClearCounterDownSource(m_counter, &status);
+  wpi_setHALError(status);
+}
+
+void Counter::SetUpDownCounterMode() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterUpDownMode(m_counter, &status);
+  wpi_setHALError(status);
+}
+
+void Counter::SetExternalDirectionMode() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterExternalDirectionMode(m_counter, &status);
+  wpi_setHALError(status);
+}
+
+void Counter::SetSemiPeriodMode(bool highSemiPeriod) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterSemiPeriodMode(m_counter, highSemiPeriod, &status);
+  wpi_setHALError(status);
+}
+
+void Counter::SetPulseLengthMode(double threshold) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterPulseLengthMode(m_counter, threshold, &status);
+  wpi_setHALError(status);
+}
+
+void Counter::SetReverseDirection(bool reverseDirection) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterReverseDirection(m_counter, reverseDirection, &status);
+  wpi_setHALError(status);
+}
+
+void Counter::SetSamplesToAverage(int samplesToAverage) {
+  if (samplesToAverage < 1 || samplesToAverage > 127) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange,
+        "Average counter values must be between 1 and 127");
+  }
+  int32_t status = 0;
+  HAL_SetCounterSamplesToAverage(m_counter, samplesToAverage, &status);
+  wpi_setHALError(status);
+}
+
+int Counter::GetSamplesToAverage() const {
+  int32_t status = 0;
+  int samples = HAL_GetCounterSamplesToAverage(m_counter, &status);
+  wpi_setHALError(status);
+  return samples;
+}
+
+int Counter::GetFPGAIndex() const { return m_index; }
+
+int Counter::Get() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetCounter(m_counter, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+void Counter::Reset() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_ResetCounter(m_counter, &status);
+  wpi_setHALError(status);
+}
+
+double Counter::GetPeriod() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetCounterPeriod(m_counter, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+void Counter::SetMaxPeriod(double maxPeriod) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterMaxPeriod(m_counter, maxPeriod, &status);
+  wpi_setHALError(status);
+}
+
+void Counter::SetUpdateWhenEmpty(bool enabled) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterUpdateWhenEmpty(m_counter, enabled, &status);
+  wpi_setHALError(status);
+}
+
+bool Counter::GetStopped() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = HAL_GetCounterStopped(m_counter, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+bool Counter::GetDirection() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = HAL_GetCounterDirection(m_counter, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+void Counter::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Counter");
+  builder.AddDoubleProperty("Value", [=]() { return Get(); }, nullptr);
+}
diff --git a/wpilibc/src/main/native/cpp/DMA.cpp b/wpilibc/src/main/native/cpp/DMA.cpp
new file mode 100644
index 0000000..1861555
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/DMA.cpp
@@ -0,0 +1,115 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/DMA.h"
+
+#include <frc/AnalogInput.h>
+#include <frc/Counter.h>
+#include <frc/DigitalSource.h>
+#include <frc/DutyCycle.h>
+#include <frc/Encoder.h>
+
+#include <hal/DMA.h>
+#include <hal/HALBase.h>
+
+using namespace frc;
+
+DMA::DMA() {
+  int32_t status = 0;
+  dmaHandle = HAL_InitializeDMA(&status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+DMA::~DMA() { HAL_FreeDMA(dmaHandle); }
+
+void DMA::SetPause(bool pause) {
+  int32_t status = 0;
+  HAL_SetDMAPause(dmaHandle, pause, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DMA::SetRate(int cycles) {
+  int32_t status = 0;
+  HAL_SetDMARate(dmaHandle, cycles, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DMA::AddEncoder(const Encoder* encoder) {
+  int32_t status = 0;
+  HAL_AddDMAEncoder(dmaHandle, encoder->m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DMA::AddEncoderPeriod(const Encoder* encoder) {
+  int32_t status = 0;
+  HAL_AddDMAEncoderPeriod(dmaHandle, encoder->m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DMA::AddCounter(const Counter* counter) {
+  int32_t status = 0;
+  HAL_AddDMACounter(dmaHandle, counter->m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DMA::AddCounterPeriod(const Counter* counter) {
+  int32_t status = 0;
+  HAL_AddDMACounterPeriod(dmaHandle, counter->m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DMA::AddDigitalSource(const DigitalSource* digitalSource) {
+  int32_t status = 0;
+  HAL_AddDMADigitalSource(dmaHandle, digitalSource->GetPortHandleForRouting(),
+                          &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DMA::AddDutyCycle(const DutyCycle* dutyCycle) {
+  int32_t status = 0;
+  HAL_AddDMADutyCycle(dmaHandle, dutyCycle->m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DMA::AddAnalogInput(const AnalogInput* analogInput) {
+  int32_t status = 0;
+  HAL_AddDMAAnalogInput(dmaHandle, analogInput->m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DMA::AddAveragedAnalogInput(const AnalogInput* analogInput) {
+  int32_t status = 0;
+  HAL_AddDMAAveragedAnalogInput(dmaHandle, analogInput->m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DMA::AddAnalogAccumulator(const AnalogInput* analogInput) {
+  int32_t status = 0;
+  HAL_AddDMAAnalogAccumulator(dmaHandle, analogInput->m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DMA::SetExternalTrigger(DigitalSource* source, bool rising, bool falling) {
+  int32_t status = 0;
+  HAL_SetDMAExternalTrigger(dmaHandle, source->GetPortHandleForRouting(),
+                            static_cast<HAL_AnalogTriggerType>(
+                                source->GetAnalogTriggerTypeForRouting()),
+                            rising, falling, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DMA::StartDMA(int queueDepth) {
+  int32_t status = 0;
+  HAL_StartDMA(dmaHandle, queueDepth, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DMA::StopDMA() {
+  int32_t status = 0;
+  HAL_StopDMA(dmaHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
diff --git a/wpilibc/src/main/native/cpp/DMC60.cpp b/wpilibc/src/main/native/cpp/DMC60.cpp
new file mode 100644
index 0000000..e7d2c65
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/DMC60.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/DMC60.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+DMC60::DMC60(int channel) : PWMSpeedController(channel) {
+  SetBounds(2.004, 1.52, 1.50, 1.48, 0.997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_DigilentDMC60, GetChannel() + 1);
+  SendableRegistry::GetInstance().SetName(this, "DMC60", GetChannel());
+}
diff --git a/wpilibc/src/main/native/cpp/DigitalGlitchFilter.cpp b/wpilibc/src/main/native/cpp/DigitalGlitchFilter.cpp
new file mode 100644
index 0000000..3cec3f1
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/DigitalGlitchFilter.cpp
@@ -0,0 +1,161 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/DigitalGlitchFilter.h"
+
+#include <algorithm>
+#include <array>
+#include <utility>
+
+#include <hal/Constants.h>
+#include <hal/DIO.h>
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/Counter.h"
+#include "frc/Encoder.h"
+#include "frc/SensorUtil.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+std::array<bool, 3> DigitalGlitchFilter::m_filterAllocated = {
+    {false, false, false}};
+wpi::mutex DigitalGlitchFilter::m_mutex;
+
+DigitalGlitchFilter::DigitalGlitchFilter() {
+  std::scoped_lock lock(m_mutex);
+  auto index =
+      std::find(m_filterAllocated.begin(), m_filterAllocated.end(), false);
+  wpi_assert(index != m_filterAllocated.end());
+
+  m_channelIndex = std::distance(m_filterAllocated.begin(), index);
+  *index = true;
+
+  HAL_Report(HALUsageReporting::kResourceType_DigitalGlitchFilter,
+             m_channelIndex + 1);
+  SendableRegistry::GetInstance().AddLW(this, "DigitalGlitchFilter",
+                                        m_channelIndex);
+}
+
+DigitalGlitchFilter::~DigitalGlitchFilter() {
+  if (m_channelIndex >= 0) {
+    std::scoped_lock lock(m_mutex);
+    m_filterAllocated[m_channelIndex] = false;
+  }
+}
+
+DigitalGlitchFilter::DigitalGlitchFilter(DigitalGlitchFilter&& rhs)
+    : ErrorBase(std::move(rhs)), SendableHelper(std::move(rhs)) {
+  std::swap(m_channelIndex, rhs.m_channelIndex);
+}
+
+DigitalGlitchFilter& DigitalGlitchFilter::operator=(DigitalGlitchFilter&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+  SendableHelper::operator=(std::move(rhs));
+
+  std::swap(m_channelIndex, rhs.m_channelIndex);
+
+  return *this;
+}
+
+void DigitalGlitchFilter::Add(DigitalSource* input) {
+  DoAdd(input, m_channelIndex + 1);
+}
+
+void DigitalGlitchFilter::DoAdd(DigitalSource* input, int requestedIndex) {
+  // Some sources from Counters and Encoders are null. By pushing the check
+  // here, we catch the issue more generally.
+  if (input) {
+    // We don't support GlitchFilters on AnalogTriggers.
+    if (input->IsAnalogTrigger()) {
+      wpi_setErrorWithContext(
+          -1, "Analog Triggers not supported for DigitalGlitchFilters");
+      return;
+    }
+    int32_t status = 0;
+    HAL_SetFilterSelect(input->GetPortHandleForRouting(), requestedIndex,
+                        &status);
+    wpi_setHALError(status);
+
+    // Validate that we set it correctly.
+    int actualIndex =
+        HAL_GetFilterSelect(input->GetPortHandleForRouting(), &status);
+    wpi_assertEqual(actualIndex, requestedIndex);
+  }
+}
+
+void DigitalGlitchFilter::Add(Encoder* input) {
+  Add(input->m_aSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Add(input->m_bSource.get());
+}
+
+void DigitalGlitchFilter::Add(Counter* input) {
+  Add(input->m_upSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Add(input->m_downSource.get());
+}
+
+void DigitalGlitchFilter::Remove(DigitalSource* input) { DoAdd(input, 0); }
+
+void DigitalGlitchFilter::Remove(Encoder* input) {
+  Remove(input->m_aSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Remove(input->m_bSource.get());
+}
+
+void DigitalGlitchFilter::Remove(Counter* input) {
+  Remove(input->m_upSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Remove(input->m_downSource.get());
+}
+
+void DigitalGlitchFilter::SetPeriodCycles(int fpgaCycles) {
+  int32_t status = 0;
+  HAL_SetFilterPeriod(m_channelIndex, fpgaCycles, &status);
+  wpi_setHALError(status);
+}
+
+void DigitalGlitchFilter::SetPeriodNanoSeconds(uint64_t nanoseconds) {
+  int32_t status = 0;
+  int fpgaCycles =
+      nanoseconds * HAL_GetSystemClockTicksPerMicrosecond() / 4 / 1000;
+  HAL_SetFilterPeriod(m_channelIndex, fpgaCycles, &status);
+
+  wpi_setHALError(status);
+}
+
+int DigitalGlitchFilter::GetPeriodCycles() {
+  int32_t status = 0;
+  int fpgaCycles = HAL_GetFilterPeriod(m_channelIndex, &status);
+
+  wpi_setHALError(status);
+
+  return fpgaCycles;
+}
+
+uint64_t DigitalGlitchFilter::GetPeriodNanoSeconds() {
+  int32_t status = 0;
+  int fpgaCycles = HAL_GetFilterPeriod(m_channelIndex, &status);
+
+  wpi_setHALError(status);
+
+  return static_cast<uint64_t>(fpgaCycles) * 1000L /
+         static_cast<uint64_t>(HAL_GetSystemClockTicksPerMicrosecond() / 4);
+}
+
+void DigitalGlitchFilter::InitSendable(SendableBuilder&) {}
diff --git a/wpilibc/src/main/native/cpp/DigitalInput.cpp b/wpilibc/src/main/native/cpp/DigitalInput.cpp
new file mode 100644
index 0000000..7210750
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/DigitalInput.cpp
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/DigitalInput.h"
+
+#include <limits>
+#include <utility>
+
+#include <hal/DIO.h>
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+#include <hal/Ports.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+DigitalInput::DigitalInput(int channel) {
+  if (!SensorUtil::CheckDigitalChannel(channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
+                               "Digital Channel " + wpi::Twine(channel));
+    m_channel = std::numeric_limits<int>::max();
+    return;
+  }
+  m_channel = channel;
+
+  int32_t status = 0;
+  m_handle = HAL_InitializeDIOPort(HAL_GetPort(channel), true, &status);
+  if (status != 0) {
+    wpi_setHALErrorWithRange(status, 0, HAL_GetNumDigitalChannels(), channel);
+    m_handle = HAL_kInvalidHandle;
+    m_channel = std::numeric_limits<int>::max();
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_DigitalInput, channel + 1);
+  SendableRegistry::GetInstance().AddLW(this, "DigitalInput", channel);
+}
+
+DigitalInput::~DigitalInput() {
+  if (StatusIsFatal()) return;
+  HAL_FreeDIOPort(m_handle);
+}
+
+bool DigitalInput::Get() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = HAL_GetDIO(m_handle, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+HAL_Handle DigitalInput::GetPortHandleForRouting() const { return m_handle; }
+
+AnalogTriggerType DigitalInput::GetAnalogTriggerTypeForRouting() const {
+  return (AnalogTriggerType)0;
+}
+
+bool DigitalInput::IsAnalogTrigger() const { return false; }
+
+void DigitalInput::SetSimDevice(HAL_SimDeviceHandle device) {
+  HAL_SetDIOSimDevice(m_handle, device);
+}
+
+int DigitalInput::GetChannel() const { return m_channel; }
+
+void DigitalInput::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Digital Input");
+  builder.AddBooleanProperty("Value", [=]() { return Get(); }, nullptr);
+}
diff --git a/wpilibc/src/main/native/cpp/DigitalOutput.cpp b/wpilibc/src/main/native/cpp/DigitalOutput.cpp
new file mode 100644
index 0000000..6e9b09b
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/DigitalOutput.cpp
@@ -0,0 +1,159 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/DigitalOutput.h"
+
+#include <limits>
+#include <utility>
+
+#include <hal/DIO.h>
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+#include <hal/Ports.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+DigitalOutput::DigitalOutput(int channel) {
+  m_pwmGenerator = HAL_kInvalidHandle;
+  if (!SensorUtil::CheckDigitalChannel(channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
+                               "Digital Channel " + wpi::Twine(channel));
+    m_channel = std::numeric_limits<int>::max();
+    return;
+  }
+  m_channel = channel;
+
+  int32_t status = 0;
+  m_handle = HAL_InitializeDIOPort(HAL_GetPort(channel), false, &status);
+  if (status != 0) {
+    wpi_setHALErrorWithRange(status, 0, HAL_GetNumDigitalChannels(), channel);
+    m_channel = std::numeric_limits<int>::max();
+    m_handle = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_DigitalOutput, channel + 1);
+  SendableRegistry::GetInstance().AddLW(this, "DigitalOutput", channel);
+}
+
+DigitalOutput::~DigitalOutput() {
+  if (StatusIsFatal()) return;
+  // Disable the PWM in case it was running.
+  DisablePWM();
+
+  HAL_FreeDIOPort(m_handle);
+}
+
+void DigitalOutput::Set(bool value) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_SetDIO(m_handle, value, &status);
+  wpi_setHALError(status);
+}
+
+bool DigitalOutput::Get() const {
+  if (StatusIsFatal()) return false;
+
+  int32_t status = 0;
+  bool val = HAL_GetDIO(m_handle, &status);
+  wpi_setHALError(status);
+  return val;
+}
+
+HAL_Handle DigitalOutput::GetPortHandleForRouting() const { return m_handle; }
+
+AnalogTriggerType DigitalOutput::GetAnalogTriggerTypeForRouting() const {
+  return (AnalogTriggerType)0;
+}
+
+bool DigitalOutput::IsAnalogTrigger() const { return false; }
+
+int DigitalOutput::GetChannel() const { return m_channel; }
+
+void DigitalOutput::Pulse(double length) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_Pulse(m_handle, length, &status);
+  wpi_setHALError(status);
+}
+
+bool DigitalOutput::IsPulsing() const {
+  if (StatusIsFatal()) return false;
+
+  int32_t status = 0;
+  bool value = HAL_IsPulsing(m_handle, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+void DigitalOutput::SetPWMRate(double rate) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_SetDigitalPWMRate(rate, &status);
+  wpi_setHALError(status);
+}
+
+void DigitalOutput::EnablePWM(double initialDutyCycle) {
+  if (m_pwmGenerator != HAL_kInvalidHandle) return;
+
+  int32_t status = 0;
+
+  if (StatusIsFatal()) return;
+  m_pwmGenerator = HAL_AllocateDigitalPWM(&status);
+  wpi_setHALError(status);
+
+  if (StatusIsFatal()) return;
+  HAL_SetDigitalPWMDutyCycle(m_pwmGenerator, initialDutyCycle, &status);
+  wpi_setHALError(status);
+
+  if (StatusIsFatal()) return;
+  HAL_SetDigitalPWMOutputChannel(m_pwmGenerator, m_channel, &status);
+  wpi_setHALError(status);
+}
+
+void DigitalOutput::DisablePWM() {
+  if (StatusIsFatal()) return;
+  if (m_pwmGenerator == HAL_kInvalidHandle) return;
+
+  int32_t status = 0;
+
+  // Disable the output by routing to a dead bit.
+  HAL_SetDigitalPWMOutputChannel(m_pwmGenerator, SensorUtil::kDigitalChannels,
+                                 &status);
+  wpi_setHALError(status);
+
+  HAL_FreeDigitalPWM(m_pwmGenerator, &status);
+  wpi_setHALError(status);
+
+  m_pwmGenerator = HAL_kInvalidHandle;
+}
+
+void DigitalOutput::UpdateDutyCycle(double dutyCycle) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_SetDigitalPWMDutyCycle(m_pwmGenerator, dutyCycle, &status);
+  wpi_setHALError(status);
+}
+
+void DigitalOutput::SetSimDevice(HAL_SimDeviceHandle device) {
+  HAL_SetDIOSimDevice(m_handle, device);
+}
+
+void DigitalOutput::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Digital Output");
+  builder.AddBooleanProperty("Value", [=]() { return Get(); },
+                             [=](bool value) { Set(value); });
+}
diff --git a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp
new file mode 100644
index 0000000..c896ea8
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp
@@ -0,0 +1,167 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/DoubleSolenoid.h"
+
+#include <utility>
+
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+#include <hal/Ports.h>
+#include <hal/Solenoid.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+DoubleSolenoid::DoubleSolenoid(int forwardChannel, int reverseChannel)
+    : DoubleSolenoid(SensorUtil::GetDefaultSolenoidModule(), forwardChannel,
+                     reverseChannel) {}
+
+DoubleSolenoid::DoubleSolenoid(int moduleNumber, int forwardChannel,
+                               int reverseChannel)
+    : SolenoidBase(moduleNumber),
+      m_forwardChannel(forwardChannel),
+      m_reverseChannel(reverseChannel) {
+  if (!SensorUtil::CheckSolenoidModule(m_moduleNumber)) {
+    wpi_setWPIErrorWithContext(ModuleIndexOutOfRange,
+                               "Solenoid Module " + wpi::Twine(m_moduleNumber));
+    return;
+  }
+  if (!SensorUtil::CheckSolenoidChannel(m_forwardChannel)) {
+    wpi_setWPIErrorWithContext(
+        ChannelIndexOutOfRange,
+        "Solenoid Channel " + wpi::Twine(m_forwardChannel));
+    return;
+  }
+  if (!SensorUtil::CheckSolenoidChannel(m_reverseChannel)) {
+    wpi_setWPIErrorWithContext(
+        ChannelIndexOutOfRange,
+        "Solenoid Channel " + wpi::Twine(m_reverseChannel));
+    return;
+  }
+  int32_t status = 0;
+  m_forwardHandle = HAL_InitializeSolenoidPort(
+      HAL_GetPortWithModule(moduleNumber, m_forwardChannel), &status);
+  if (status != 0) {
+    wpi_setHALErrorWithRange(status, 0, HAL_GetNumSolenoidChannels(),
+                             forwardChannel);
+    m_forwardHandle = HAL_kInvalidHandle;
+    m_reverseHandle = HAL_kInvalidHandle;
+    return;
+  }
+
+  m_reverseHandle = HAL_InitializeSolenoidPort(
+      HAL_GetPortWithModule(moduleNumber, m_reverseChannel), &status);
+  if (status != 0) {
+    wpi_setHALErrorWithRange(status, 0, HAL_GetNumSolenoidChannels(),
+                             reverseChannel);
+    // free forward solenoid
+    HAL_FreeSolenoidPort(m_forwardHandle);
+    m_forwardHandle = HAL_kInvalidHandle;
+    m_reverseHandle = HAL_kInvalidHandle;
+    return;
+  }
+
+  m_forwardMask = 1 << m_forwardChannel;
+  m_reverseMask = 1 << m_reverseChannel;
+
+  HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_forwardChannel + 1,
+             m_moduleNumber + 1);
+  HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_reverseChannel + 1,
+             m_moduleNumber + 1);
+
+  SendableRegistry::GetInstance().AddLW(this, "DoubleSolenoid", m_moduleNumber,
+                                        m_forwardChannel);
+}
+
+DoubleSolenoid::~DoubleSolenoid() {
+  HAL_FreeSolenoidPort(m_forwardHandle);
+  HAL_FreeSolenoidPort(m_reverseHandle);
+}
+
+void DoubleSolenoid::Set(Value value) {
+  if (StatusIsFatal()) return;
+
+  bool forward = false;
+  bool reverse = false;
+  switch (value) {
+    case kOff:
+      forward = false;
+      reverse = false;
+      break;
+    case kForward:
+      forward = true;
+      reverse = false;
+      break;
+    case kReverse:
+      forward = false;
+      reverse = true;
+      break;
+  }
+  int fstatus = 0;
+  HAL_SetSolenoid(m_forwardHandle, forward, &fstatus);
+  int rstatus = 0;
+  HAL_SetSolenoid(m_reverseHandle, reverse, &rstatus);
+
+  wpi_setHALError(fstatus);
+  wpi_setHALError(rstatus);
+}
+
+DoubleSolenoid::Value DoubleSolenoid::Get() const {
+  if (StatusIsFatal()) return kOff;
+  int fstatus = 0;
+  int rstatus = 0;
+  bool valueForward = HAL_GetSolenoid(m_forwardHandle, &fstatus);
+  bool valueReverse = HAL_GetSolenoid(m_reverseHandle, &rstatus);
+
+  wpi_setHALError(fstatus);
+  wpi_setHALError(rstatus);
+
+  if (valueForward) return kForward;
+  if (valueReverse) return kReverse;
+  return kOff;
+}
+
+bool DoubleSolenoid::IsFwdSolenoidBlackListed() const {
+  int blackList = GetPCMSolenoidBlackList(m_moduleNumber);
+  return (blackList & m_forwardMask) != 0;
+}
+
+bool DoubleSolenoid::IsRevSolenoidBlackListed() const {
+  int blackList = GetPCMSolenoidBlackList(m_moduleNumber);
+  return (blackList & m_reverseMask) != 0;
+}
+
+void DoubleSolenoid::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Double Solenoid");
+  builder.SetActuator(true);
+  builder.SetSafeState([=]() { Set(kOff); });
+  builder.AddSmallStringProperty(
+      "Value",
+      [=](wpi::SmallVectorImpl<char>& buf) -> wpi::StringRef {
+        switch (Get()) {
+          case kForward:
+            return "Forward";
+          case kReverse:
+            return "Reverse";
+          default:
+            return "Off";
+        }
+      },
+      [=](wpi::StringRef value) {
+        Value lvalue = kOff;
+        if (value == "Forward")
+          lvalue = kForward;
+        else if (value == "Reverse")
+          lvalue = kReverse;
+        Set(lvalue);
+      });
+}
diff --git a/wpilibc/src/main/native/cpp/DriverStation.cpp b/wpilibc/src/main/native/cpp/DriverStation.cpp
new file mode 100644
index 0000000..7c64883
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/DriverStation.cpp
@@ -0,0 +1,615 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/DriverStation.h"
+
+#include <chrono>
+
+#include <hal/DriverStation.h>
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+#include <hal/Power.h>
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/SmallString.h>
+#include <wpi/StringRef.h>
+
+#include "frc/AnalogInput.h"
+#include "frc/MotorSafety.h"
+#include "frc/Timer.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+
+namespace frc {
+
+class MatchDataSender {
+ public:
+  std::shared_ptr<nt::NetworkTable> table;
+  nt::NetworkTableEntry typeMetadata;
+  nt::NetworkTableEntry gameSpecificMessage;
+  nt::NetworkTableEntry eventName;
+  nt::NetworkTableEntry matchNumber;
+  nt::NetworkTableEntry replayNumber;
+  nt::NetworkTableEntry matchType;
+  nt::NetworkTableEntry alliance;
+  nt::NetworkTableEntry station;
+  nt::NetworkTableEntry controlWord;
+
+  MatchDataSender() {
+    table = nt::NetworkTableInstance::GetDefault().GetTable("FMSInfo");
+    typeMetadata = table->GetEntry(".type");
+    typeMetadata.ForceSetString("FMSInfo");
+    gameSpecificMessage = table->GetEntry("GameSpecificMessage");
+    gameSpecificMessage.ForceSetString("");
+    eventName = table->GetEntry("EventName");
+    eventName.ForceSetString("");
+    matchNumber = table->GetEntry("MatchNumber");
+    matchNumber.ForceSetDouble(0);
+    replayNumber = table->GetEntry("ReplayNumber");
+    replayNumber.ForceSetDouble(0);
+    matchType = table->GetEntry("MatchType");
+    matchType.ForceSetDouble(0);
+    alliance = table->GetEntry("IsRedAlliance");
+    alliance.ForceSetBoolean(true);
+    station = table->GetEntry("StationNumber");
+    station.ForceSetDouble(1);
+    controlWord = table->GetEntry("FMSControlData");
+    controlWord.ForceSetDouble(0);
+  }
+};
+}  // namespace frc
+
+using namespace frc;
+
+static constexpr double kJoystickUnpluggedMessageInterval = 1.0;
+
+DriverStation::~DriverStation() {
+  m_isRunning = false;
+  // Trigger a DS mutex release in case there is no driver station running.
+  HAL_ReleaseDSMutex();
+  m_dsThread.join();
+}
+
+DriverStation& DriverStation::GetInstance() {
+  static DriverStation instance;
+  return instance;
+}
+
+void DriverStation::ReportError(const wpi::Twine& error) {
+  wpi::SmallString<128> temp;
+  HAL_SendError(1, 1, 0, error.toNullTerminatedStringRef(temp).data(), "", "",
+                1);
+}
+
+void DriverStation::ReportWarning(const wpi::Twine& error) {
+  wpi::SmallString<128> temp;
+  HAL_SendError(0, 1, 0, error.toNullTerminatedStringRef(temp).data(), "", "",
+                1);
+}
+
+void DriverStation::ReportError(bool isError, int32_t code,
+                                const wpi::Twine& error,
+                                const wpi::Twine& location,
+                                const wpi::Twine& stack) {
+  wpi::SmallString<128> errorTemp;
+  wpi::SmallString<128> locationTemp;
+  wpi::SmallString<128> stackTemp;
+  HAL_SendError(isError, code, 0,
+                error.toNullTerminatedStringRef(errorTemp).data(),
+                location.toNullTerminatedStringRef(locationTemp).data(),
+                stack.toNullTerminatedStringRef(stackTemp).data(), 1);
+}
+
+bool DriverStation::GetStickButton(int stick, int button) {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return false;
+  }
+  if (button <= 0) {
+    ReportJoystickUnpluggedError(
+        "ERROR: Button indexes begin at 1 in WPILib for C++ and Java");
+    return false;
+  }
+
+  HAL_JoystickButtons buttons;
+  HAL_GetJoystickButtons(stick, &buttons);
+
+  if (button > buttons.count) {
+    ReportJoystickUnpluggedWarning(
+        "Joystick Button missing, check if all controllers are plugged in");
+    return false;
+  }
+
+  return buttons.buttons & 1 << (button - 1);
+}
+
+bool DriverStation::GetStickButtonPressed(int stick, int button) {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return false;
+  }
+  if (button <= 0) {
+    ReportJoystickUnpluggedError(
+        "ERROR: Button indexes begin at 1 in WPILib for C++ and Java");
+    return false;
+  }
+
+  HAL_JoystickButtons buttons;
+  HAL_GetJoystickButtons(stick, &buttons);
+
+  if (button > buttons.count) {
+    ReportJoystickUnpluggedWarning(
+        "Joystick Button missing, check if all controllers are plugged in");
+    return false;
+  }
+  std::unique_lock lock(m_buttonEdgeMutex);
+  // If button was pressed, clear flag and return true
+  if (m_joystickButtonsPressed[stick] & 1 << (button - 1)) {
+    m_joystickButtonsPressed[stick] &= ~(1 << (button - 1));
+    return true;
+  } else {
+    return false;
+  }
+}
+
+bool DriverStation::GetStickButtonReleased(int stick, int button) {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return false;
+  }
+  if (button <= 0) {
+    ReportJoystickUnpluggedError(
+        "ERROR: Button indexes begin at 1 in WPILib for C++ and Java");
+    return false;
+  }
+
+  HAL_JoystickButtons buttons;
+  HAL_GetJoystickButtons(stick, &buttons);
+
+  if (button > buttons.count) {
+    ReportJoystickUnpluggedWarning(
+        "Joystick Button missing, check if all controllers are plugged in");
+    return false;
+  }
+  std::unique_lock lock(m_buttonEdgeMutex);
+  // If button was released, clear flag and return true
+  if (m_joystickButtonsReleased[stick] & 1 << (button - 1)) {
+    m_joystickButtonsReleased[stick] &= ~(1 << (button - 1));
+    return true;
+  } else {
+    return false;
+  }
+}
+
+double DriverStation::GetStickAxis(int stick, int axis) {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0.0;
+  }
+  if (axis < 0 || axis >= HAL_kMaxJoystickAxes) {
+    wpi_setWPIError(BadJoystickAxis);
+    return 0.0;
+  }
+
+  HAL_JoystickAxes axes;
+  HAL_GetJoystickAxes(stick, &axes);
+
+  if (axis >= axes.count) {
+    ReportJoystickUnpluggedWarning(
+        "Joystick Axis missing, check if all controllers are plugged in");
+    return 0.0;
+  }
+
+  return axes.axes[axis];
+}
+
+int DriverStation::GetStickPOV(int stick, int pov) {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return -1;
+  }
+  if (pov < 0 || pov >= HAL_kMaxJoystickPOVs) {
+    wpi_setWPIError(BadJoystickAxis);
+    return -1;
+  }
+
+  HAL_JoystickPOVs povs;
+  HAL_GetJoystickPOVs(stick, &povs);
+
+  if (pov >= povs.count) {
+    ReportJoystickUnpluggedWarning(
+        "Joystick POV missing, check if all controllers are plugged in");
+    return -1;
+  }
+
+  return povs.povs[pov];
+}
+
+int DriverStation::GetStickButtons(int stick) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+
+  HAL_JoystickButtons buttons;
+  HAL_GetJoystickButtons(stick, &buttons);
+
+  return buttons.buttons;
+}
+
+int DriverStation::GetStickAxisCount(int stick) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+
+  HAL_JoystickAxes axes;
+  HAL_GetJoystickAxes(stick, &axes);
+
+  return axes.count;
+}
+
+int DriverStation::GetStickPOVCount(int stick) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+
+  HAL_JoystickPOVs povs;
+  HAL_GetJoystickPOVs(stick, &povs);
+
+  return povs.count;
+}
+
+int DriverStation::GetStickButtonCount(int stick) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+
+  HAL_JoystickButtons buttons;
+  HAL_GetJoystickButtons(stick, &buttons);
+
+  return buttons.count;
+}
+
+bool DriverStation::GetJoystickIsXbox(int stick) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return false;
+  }
+
+  HAL_JoystickDescriptor descriptor;
+  HAL_GetJoystickDescriptor(stick, &descriptor);
+
+  return static_cast<bool>(descriptor.isXbox);
+}
+
+int DriverStation::GetJoystickType(int stick) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return -1;
+  }
+
+  HAL_JoystickDescriptor descriptor;
+  HAL_GetJoystickDescriptor(stick, &descriptor);
+
+  return static_cast<int>(descriptor.type);
+}
+
+std::string DriverStation::GetJoystickName(int stick) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+  }
+
+  HAL_JoystickDescriptor descriptor;
+  HAL_GetJoystickDescriptor(stick, &descriptor);
+
+  return descriptor.name;
+}
+
+int DriverStation::GetJoystickAxisType(int stick, int axis) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return -1;
+  }
+
+  HAL_JoystickDescriptor descriptor;
+  HAL_GetJoystickDescriptor(stick, &descriptor);
+
+  return static_cast<bool>(descriptor.axisTypes);
+}
+
+bool DriverStation::IsEnabled() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return controlWord.enabled && controlWord.dsAttached;
+}
+
+bool DriverStation::IsDisabled() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return !(controlWord.enabled && controlWord.dsAttached);
+}
+
+bool DriverStation::IsEStopped() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return controlWord.eStop;
+}
+
+bool DriverStation::IsAutonomous() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return controlWord.autonomous;
+}
+
+bool DriverStation::IsOperatorControl() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return !(controlWord.autonomous || controlWord.test);
+}
+
+bool DriverStation::IsTest() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return controlWord.test;
+}
+
+bool DriverStation::IsDSAttached() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return controlWord.dsAttached;
+}
+
+bool DriverStation::IsNewControlData() const { return HAL_IsNewControlData(); }
+
+bool DriverStation::IsFMSAttached() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return controlWord.fmsAttached;
+}
+
+std::string DriverStation::GetGameSpecificMessage() const {
+  HAL_MatchInfo info;
+  HAL_GetMatchInfo(&info);
+  return std::string(reinterpret_cast<char*>(info.gameSpecificMessage),
+                     info.gameSpecificMessageSize);
+}
+
+std::string DriverStation::GetEventName() const {
+  HAL_MatchInfo info;
+  HAL_GetMatchInfo(&info);
+  return info.eventName;
+}
+
+DriverStation::MatchType DriverStation::GetMatchType() const {
+  HAL_MatchInfo info;
+  HAL_GetMatchInfo(&info);
+  return static_cast<DriverStation::MatchType>(info.matchType);
+}
+
+int DriverStation::GetMatchNumber() const {
+  HAL_MatchInfo info;
+  HAL_GetMatchInfo(&info);
+  return info.matchNumber;
+}
+
+int DriverStation::GetReplayNumber() const {
+  HAL_MatchInfo info;
+  HAL_GetMatchInfo(&info);
+  return info.replayNumber;
+}
+
+DriverStation::Alliance DriverStation::GetAlliance() const {
+  int32_t status = 0;
+  auto allianceStationID = HAL_GetAllianceStation(&status);
+  switch (allianceStationID) {
+    case HAL_AllianceStationID_kRed1:
+    case HAL_AllianceStationID_kRed2:
+    case HAL_AllianceStationID_kRed3:
+      return kRed;
+    case HAL_AllianceStationID_kBlue1:
+    case HAL_AllianceStationID_kBlue2:
+    case HAL_AllianceStationID_kBlue3:
+      return kBlue;
+    default:
+      return kInvalid;
+  }
+}
+
+int DriverStation::GetLocation() const {
+  int32_t status = 0;
+  auto allianceStationID = HAL_GetAllianceStation(&status);
+  switch (allianceStationID) {
+    case HAL_AllianceStationID_kRed1:
+    case HAL_AllianceStationID_kBlue1:
+      return 1;
+    case HAL_AllianceStationID_kRed2:
+    case HAL_AllianceStationID_kBlue2:
+      return 2;
+    case HAL_AllianceStationID_kRed3:
+    case HAL_AllianceStationID_kBlue3:
+      return 3;
+    default:
+      return 0;
+  }
+}
+
+void DriverStation::WaitForData() { WaitForData(0); }
+
+bool DriverStation::WaitForData(double timeout) {
+  auto timeoutTime =
+      std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
+
+  std::unique_lock lock(m_waitForDataMutex);
+  int currentCount = m_waitForDataCounter;
+  while (m_waitForDataCounter == currentCount) {
+    if (timeout > 0) {
+      auto timedOut = m_waitForDataCond.wait_until(lock, timeoutTime);
+      if (timedOut == std::cv_status::timeout) {
+        return false;
+      }
+    } else {
+      m_waitForDataCond.wait(lock);
+    }
+  }
+  return true;
+}
+
+double DriverStation::GetMatchTime() const {
+  int32_t status;
+  return HAL_GetMatchTime(&status);
+}
+
+double DriverStation::GetBatteryVoltage() const {
+  int32_t status = 0;
+  double voltage = HAL_GetVinVoltage(&status);
+  wpi_setErrorWithContext(status, "getVinVoltage");
+
+  return voltage;
+}
+
+void DriverStation::WakeupWaitForData() {
+  std::scoped_lock waitLock(m_waitForDataMutex);
+  // Nofify all threads
+  m_waitForDataCounter++;
+  m_waitForDataCond.notify_all();
+}
+
+void DriverStation::GetData() {
+  {
+    // Compute the pressed and released buttons
+    HAL_JoystickButtons currentButtons;
+    std::unique_lock lock(m_buttonEdgeMutex);
+
+    for (int32_t i = 0; i < kJoystickPorts; i++) {
+      HAL_GetJoystickButtons(i, &currentButtons);
+
+      // If buttons weren't pressed and are now, set flags in m_buttonsPressed
+      m_joystickButtonsPressed[i] |=
+          ~m_previousButtonStates[i].buttons & currentButtons.buttons;
+
+      // If buttons were pressed and aren't now, set flags in m_buttonsReleased
+      m_joystickButtonsReleased[i] |=
+          m_previousButtonStates[i].buttons & ~currentButtons.buttons;
+
+      m_previousButtonStates[i] = currentButtons;
+    }
+  }
+
+  WakeupWaitForData();
+  SendMatchData();
+}
+
+DriverStation::DriverStation() {
+  HAL_Initialize(500, 0);
+  m_waitForDataCounter = 0;
+
+  m_matchDataSender = std::make_unique<MatchDataSender>();
+
+  // All joysticks should default to having zero axes, povs and buttons, so
+  // uninitialized memory doesn't get sent to speed controllers.
+  for (unsigned int i = 0; i < kJoystickPorts; i++) {
+    m_joystickButtonsPressed[i] = 0;
+    m_joystickButtonsReleased[i] = 0;
+    m_previousButtonStates[i].count = 0;
+    m_previousButtonStates[i].buttons = 0;
+  }
+
+  m_dsThread = std::thread(&DriverStation::Run, this);
+}
+
+void DriverStation::ReportJoystickUnpluggedError(const wpi::Twine& message) {
+  double currentTime = Timer::GetFPGATimestamp();
+  if (currentTime > m_nextMessageTime) {
+    ReportError(message);
+    m_nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;
+  }
+}
+
+void DriverStation::ReportJoystickUnpluggedWarning(const wpi::Twine& message) {
+  double currentTime = Timer::GetFPGATimestamp();
+  if (currentTime > m_nextMessageTime) {
+    ReportWarning(message);
+    m_nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;
+  }
+}
+
+void DriverStation::Run() {
+  m_isRunning = true;
+  int safetyCounter = 0;
+  while (m_isRunning) {
+    HAL_WaitForDSData();
+    GetData();
+
+    if (IsDisabled()) safetyCounter = 0;
+
+    if (++safetyCounter >= 4) {
+      MotorSafety::CheckMotors();
+      safetyCounter = 0;
+    }
+    if (m_userInDisabled) HAL_ObserveUserProgramDisabled();
+    if (m_userInAutonomous) HAL_ObserveUserProgramAutonomous();
+    if (m_userInTeleop) HAL_ObserveUserProgramTeleop();
+    if (m_userInTest) HAL_ObserveUserProgramTest();
+  }
+}
+
+void DriverStation::SendMatchData() {
+  int32_t status = 0;
+  HAL_AllianceStationID alliance = HAL_GetAllianceStation(&status);
+  bool isRedAlliance = false;
+  int stationNumber = 1;
+  switch (alliance) {
+    case HAL_AllianceStationID::HAL_AllianceStationID_kBlue1:
+      isRedAlliance = false;
+      stationNumber = 1;
+      break;
+    case HAL_AllianceStationID::HAL_AllianceStationID_kBlue2:
+      isRedAlliance = false;
+      stationNumber = 2;
+      break;
+    case HAL_AllianceStationID::HAL_AllianceStationID_kBlue3:
+      isRedAlliance = false;
+      stationNumber = 3;
+      break;
+    case HAL_AllianceStationID::HAL_AllianceStationID_kRed1:
+      isRedAlliance = true;
+      stationNumber = 1;
+      break;
+    case HAL_AllianceStationID::HAL_AllianceStationID_kRed2:
+      isRedAlliance = true;
+      stationNumber = 2;
+      break;
+    default:
+      isRedAlliance = true;
+      stationNumber = 3;
+      break;
+  }
+
+  HAL_MatchInfo tmpDataStore;
+  HAL_GetMatchInfo(&tmpDataStore);
+
+  m_matchDataSender->alliance.SetBoolean(isRedAlliance);
+  m_matchDataSender->station.SetDouble(stationNumber);
+  m_matchDataSender->eventName.SetString(tmpDataStore.eventName);
+  m_matchDataSender->gameSpecificMessage.SetString(
+      std::string(reinterpret_cast<char*>(tmpDataStore.gameSpecificMessage),
+                  tmpDataStore.gameSpecificMessageSize));
+  m_matchDataSender->matchNumber.SetDouble(tmpDataStore.matchNumber);
+  m_matchDataSender->replayNumber.SetDouble(tmpDataStore.replayNumber);
+  m_matchDataSender->matchType.SetDouble(
+      static_cast<int>(tmpDataStore.matchType));
+
+  HAL_ControlWord ctlWord;
+  HAL_GetControlWord(&ctlWord);
+  int32_t wordInt = 0;
+  std::memcpy(&wordInt, &ctlWord, sizeof(wordInt));
+  m_matchDataSender->controlWord.SetDouble(wordInt);
+}
diff --git a/wpilibc/src/main/native/cpp/DutyCycle.cpp b/wpilibc/src/main/native/cpp/DutyCycle.cpp
new file mode 100644
index 0000000..12f390e
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/DutyCycle.cpp
@@ -0,0 +1,100 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/DutyCycle.h"
+
+#include <hal/DutyCycle.h>
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/DigitalSource.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+DutyCycle::DutyCycle(DigitalSource* source)
+    : m_source{source, NullDeleter<DigitalSource>()} {
+  if (m_source == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitDutyCycle();
+  }
+}
+
+DutyCycle::DutyCycle(DigitalSource& source)
+    : m_source{&source, NullDeleter<DigitalSource>()} {
+  InitDutyCycle();
+}
+
+DutyCycle::DutyCycle(std::shared_ptr<DigitalSource> source)
+    : m_source{std::move(source)} {
+  if (m_source == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitDutyCycle();
+  }
+}
+
+DutyCycle::~DutyCycle() { HAL_FreeDutyCycle(m_handle); }
+
+void DutyCycle::InitDutyCycle() {
+  int32_t status = 0;
+  m_handle =
+      HAL_InitializeDutyCycle(m_source->GetPortHandleForRouting(),
+                              static_cast<HAL_AnalogTriggerType>(
+                                  m_source->GetAnalogTriggerTypeForRouting()),
+                              &status);
+  wpi_setHALError(status);
+  int index = GetFPGAIndex();
+  HAL_Report(HALUsageReporting::kResourceType_DutyCycle, index + 1);
+  SendableRegistry::GetInstance().AddLW(this, "Duty Cycle", index);
+}
+
+int DutyCycle::GetFPGAIndex() const {
+  int32_t status = 0;
+  auto retVal = HAL_GetDutyCycleFPGAIndex(m_handle, &status);
+  wpi_setHALError(status);
+  return retVal;
+}
+
+int DutyCycle::GetFrequency() const {
+  int32_t status = 0;
+  auto retVal = HAL_GetDutyCycleFrequency(m_handle, &status);
+  wpi_setHALError(status);
+  return retVal;
+}
+
+double DutyCycle::GetOutput() const {
+  int32_t status = 0;
+  auto retVal = HAL_GetDutyCycleOutput(m_handle, &status);
+  wpi_setHALError(status);
+  return retVal;
+}
+
+unsigned int DutyCycle::GetOutputRaw() const {
+  int32_t status = 0;
+  auto retVal = HAL_GetDutyCycleOutputRaw(m_handle, &status);
+  wpi_setHALError(status);
+  return retVal;
+}
+
+unsigned int DutyCycle::GetOutputScaleFactor() const {
+  int32_t status = 0;
+  auto retVal = HAL_GetDutyCycleOutputScaleFactor(m_handle, &status);
+  wpi_setHALError(status);
+  return retVal;
+}
+
+int DutyCycle::GetSourceChannel() const { return m_source->GetChannel(); }
+
+void DutyCycle::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Duty Cycle");
+  builder.AddDoubleProperty("Frequency",
+                            [this] { return this->GetFrequency(); }, nullptr);
+  builder.AddDoubleProperty("Output", [this] { return this->GetOutput(); },
+                            nullptr);
+}
diff --git a/wpilibc/src/main/native/cpp/DutyCycleEncoder.cpp b/wpilibc/src/main/native/cpp/DutyCycleEncoder.cpp
new file mode 100644
index 0000000..ea054ce
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/DutyCycleEncoder.cpp
@@ -0,0 +1,152 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/DutyCycleEncoder.h"
+
+#include "frc/Counter.h"
+#include "frc/DigitalInput.h"
+#include "frc/DigitalSource.h"
+#include "frc/DriverStation.h"
+#include "frc/DutyCycle.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+DutyCycleEncoder::DutyCycleEncoder(int channel)
+    : m_dutyCycle{std::make_shared<DutyCycle>(
+          std::make_shared<DigitalInput>(channel))},
+      m_analogTrigger{m_dutyCycle.get()},
+      m_counter{} {
+  Init();
+}
+
+DutyCycleEncoder::DutyCycleEncoder(DutyCycle& dutyCycle)
+    : m_dutyCycle{&dutyCycle, NullDeleter<DutyCycle>{}},
+      m_analogTrigger{m_dutyCycle.get()},
+      m_counter{} {
+  Init();
+}
+
+DutyCycleEncoder::DutyCycleEncoder(DutyCycle* dutyCycle)
+    : m_dutyCycle{dutyCycle, NullDeleter<DutyCycle>{}},
+      m_analogTrigger{m_dutyCycle.get()},
+      m_counter{} {
+  Init();
+}
+
+DutyCycleEncoder::DutyCycleEncoder(std::shared_ptr<DutyCycle> dutyCycle)
+    : m_dutyCycle{std::move(dutyCycle)},
+      m_analogTrigger{m_dutyCycle.get()},
+      m_counter{} {
+  Init();
+}
+
+DutyCycleEncoder::DutyCycleEncoder(DigitalSource& digitalSource)
+    : m_dutyCycle{std::make_shared<DutyCycle>(digitalSource)},
+      m_analogTrigger{m_dutyCycle.get()},
+      m_counter{} {
+  Init();
+}
+
+DutyCycleEncoder::DutyCycleEncoder(DigitalSource* digitalSource)
+    : m_dutyCycle{std::make_shared<DutyCycle>(digitalSource)},
+      m_analogTrigger{m_dutyCycle.get()},
+      m_counter{} {
+  Init();
+}
+
+DutyCycleEncoder::DutyCycleEncoder(std::shared_ptr<DigitalSource> digitalSource)
+    : m_dutyCycle{std::make_shared<DutyCycle>(digitalSource)},
+      m_analogTrigger{m_dutyCycle.get()},
+      m_counter{} {
+  Init();
+}
+
+void DutyCycleEncoder::Init() {
+  m_simDevice = hal::SimDevice{"DutyCycleEncoder", m_dutyCycle->GetFPGAIndex()};
+
+  if (m_simDevice) {
+    m_simPosition = m_simDevice.CreateDouble("Position", false, 0.0);
+    m_simIsConnected = m_simDevice.CreateBoolean("Connected", false, true);
+  }
+
+  m_analogTrigger.SetLimitsDutyCycle(0.25, 0.75);
+  m_counter.SetUpSource(
+      m_analogTrigger.CreateOutput(AnalogTriggerType::kRisingPulse));
+  m_counter.SetDownSource(
+      m_analogTrigger.CreateOutput(AnalogTriggerType::kFallingPulse));
+
+  SendableRegistry::GetInstance().AddLW(this, "DutyCycle Encoder",
+                                        m_dutyCycle->GetSourceChannel());
+}
+
+units::turn_t DutyCycleEncoder::Get() const {
+  if (m_simPosition) return units::turn_t{m_simPosition.Get()};
+
+  // As the values are not atomic, keep trying until we get 2 reads of the same
+  // value If we don't within 10 attempts, error
+  for (int i = 0; i < 10; i++) {
+    auto counter = m_counter.Get();
+    auto pos = m_dutyCycle->GetOutput();
+    auto counter2 = m_counter.Get();
+    auto pos2 = m_dutyCycle->GetOutput();
+    if (counter == counter2 && pos == pos2) {
+      units::turn_t turns{counter + pos - m_positionOffset};
+      m_lastPosition = turns;
+      return turns;
+    }
+  }
+
+  frc::DriverStation::GetInstance().ReportWarning(
+      "Failed to read DutyCycle Encoder. Potential Speed Overrun. Returning "
+      "last value");
+  return m_lastPosition;
+}
+
+void DutyCycleEncoder::SetDistancePerRotation(double distancePerRotation) {
+  m_distancePerRotation = distancePerRotation;
+}
+
+double DutyCycleEncoder::GetDistancePerRotation() const {
+  return m_distancePerRotation;
+}
+
+double DutyCycleEncoder::GetDistance() const {
+  return Get().to<double>() * GetDistancePerRotation();
+}
+
+int DutyCycleEncoder::GetFrequency() const {
+  return m_dutyCycle->GetFrequency();
+}
+
+void DutyCycleEncoder::Reset() {
+  m_counter.Reset();
+  m_positionOffset = m_dutyCycle->GetOutput();
+}
+
+bool DutyCycleEncoder::IsConnected() const {
+  if (m_simIsConnected) return m_simIsConnected.Get();
+  return GetFrequency() > m_frequencyThreshold;
+}
+
+void DutyCycleEncoder::SetConnectedFrequencyThreshold(int frequency) {
+  if (frequency < 0) {
+    frequency = 0;
+  }
+  m_frequencyThreshold = frequency;
+}
+
+void DutyCycleEncoder::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("AbsoluteEncoder");
+  builder.AddDoubleProperty("Distance", [this] { return this->GetDistance(); },
+                            nullptr);
+  builder.AddDoubleProperty("Distance Per Rotation",
+                            [this] { return this->GetDistancePerRotation(); },
+                            nullptr);
+  builder.AddDoubleProperty("Is Connected",
+                            [this] { return this->IsConnected(); }, nullptr);
+}
diff --git a/wpilibc/src/main/native/cpp/Encoder.cpp b/wpilibc/src/main/native/cpp/Encoder.cpp
new file mode 100644
index 0000000..963bcc6
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Encoder.cpp
@@ -0,0 +1,268 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Encoder.h"
+
+#include <utility>
+
+#include <hal/Encoder.h>
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/DigitalInput.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+Encoder::Encoder(int aChannel, int bChannel, bool reverseDirection,
+                 EncodingType encodingType) {
+  m_aSource = std::make_shared<DigitalInput>(aChannel);
+  m_bSource = std::make_shared<DigitalInput>(bChannel);
+  InitEncoder(reverseDirection, encodingType);
+  auto& registry = SendableRegistry::GetInstance();
+  registry.AddChild(this, m_aSource.get());
+  registry.AddChild(this, m_bSource.get());
+}
+
+Encoder::Encoder(DigitalSource* aSource, DigitalSource* bSource,
+                 bool reverseDirection, EncodingType encodingType)
+    : m_aSource(aSource, NullDeleter<DigitalSource>()),
+      m_bSource(bSource, NullDeleter<DigitalSource>()) {
+  if (m_aSource == nullptr || m_bSource == nullptr)
+    wpi_setWPIError(NullParameter);
+  else
+    InitEncoder(reverseDirection, encodingType);
+}
+
+Encoder::Encoder(DigitalSource& aSource, DigitalSource& bSource,
+                 bool reverseDirection, EncodingType encodingType)
+    : m_aSource(&aSource, NullDeleter<DigitalSource>()),
+      m_bSource(&bSource, NullDeleter<DigitalSource>()) {
+  InitEncoder(reverseDirection, encodingType);
+}
+
+Encoder::Encoder(std::shared_ptr<DigitalSource> aSource,
+                 std::shared_ptr<DigitalSource> bSource, bool reverseDirection,
+                 EncodingType encodingType)
+    : m_aSource(aSource), m_bSource(bSource) {
+  if (m_aSource == nullptr || m_bSource == nullptr)
+    wpi_setWPIError(NullParameter);
+  else
+    InitEncoder(reverseDirection, encodingType);
+}
+
+Encoder::~Encoder() {
+  int32_t status = 0;
+  HAL_FreeEncoder(m_encoder, &status);
+  wpi_setHALError(status);
+}
+
+int Encoder::Get() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetEncoder(m_encoder, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+void Encoder::Reset() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_ResetEncoder(m_encoder, &status);
+  wpi_setHALError(status);
+}
+
+double Encoder::GetPeriod() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetEncoderPeriod(m_encoder, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+void Encoder::SetMaxPeriod(double maxPeriod) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetEncoderMaxPeriod(m_encoder, maxPeriod, &status);
+  wpi_setHALError(status);
+}
+
+bool Encoder::GetStopped() const {
+  if (StatusIsFatal()) return true;
+  int32_t status = 0;
+  bool value = HAL_GetEncoderStopped(m_encoder, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+bool Encoder::GetDirection() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = HAL_GetEncoderDirection(m_encoder, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+int Encoder::GetRaw() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetEncoderRaw(m_encoder, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+int Encoder::GetEncodingScale() const {
+  int32_t status = 0;
+  int val = HAL_GetEncoderEncodingScale(m_encoder, &status);
+  wpi_setHALError(status);
+  return val;
+}
+
+double Encoder::GetDistance() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetEncoderDistance(m_encoder, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+double Encoder::GetRate() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetEncoderRate(m_encoder, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+void Encoder::SetMinRate(double minRate) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetEncoderMinRate(m_encoder, minRate, &status);
+  wpi_setHALError(status);
+}
+
+void Encoder::SetDistancePerPulse(double distancePerPulse) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetEncoderDistancePerPulse(m_encoder, distancePerPulse, &status);
+  wpi_setHALError(status);
+}
+
+double Encoder::GetDistancePerPulse() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double distancePerPulse = HAL_GetEncoderDistancePerPulse(m_encoder, &status);
+  wpi_setHALError(status);
+  return distancePerPulse;
+}
+
+void Encoder::SetReverseDirection(bool reverseDirection) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetEncoderReverseDirection(m_encoder, reverseDirection, &status);
+  wpi_setHALError(status);
+}
+
+void Encoder::SetSamplesToAverage(int samplesToAverage) {
+  if (samplesToAverage < 1 || samplesToAverage > 127) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange,
+        "Average counter values must be between 1 and 127");
+    return;
+  }
+  int32_t status = 0;
+  HAL_SetEncoderSamplesToAverage(m_encoder, samplesToAverage, &status);
+  wpi_setHALError(status);
+}
+
+int Encoder::GetSamplesToAverage() const {
+  int32_t status = 0;
+  int result = HAL_GetEncoderSamplesToAverage(m_encoder, &status);
+  wpi_setHALError(status);
+  return result;
+}
+
+double Encoder::PIDGet() {
+  if (StatusIsFatal()) return 0.0;
+  switch (GetPIDSourceType()) {
+    case PIDSourceType::kDisplacement:
+      return GetDistance();
+    case PIDSourceType::kRate:
+      return GetRate();
+    default:
+      return 0.0;
+  }
+}
+
+void Encoder::SetIndexSource(int channel, Encoder::IndexingType type) {
+  // Force digital input if just given an index
+  m_indexSource = std::make_shared<DigitalInput>(channel);
+  SendableRegistry::GetInstance().AddChild(this, m_indexSource.get());
+  SetIndexSource(*m_indexSource.get(), type);
+}
+
+void Encoder::SetIndexSource(const DigitalSource& source,
+                             Encoder::IndexingType type) {
+  int32_t status = 0;
+  HAL_SetEncoderIndexSource(
+      m_encoder, source.GetPortHandleForRouting(),
+      (HAL_AnalogTriggerType)source.GetAnalogTriggerTypeForRouting(),
+      (HAL_EncoderIndexingType)type, &status);
+  wpi_setHALError(status);
+}
+
+void Encoder::SetSimDevice(HAL_SimDeviceHandle device) {
+  HAL_SetEncoderSimDevice(m_encoder, device);
+}
+
+int Encoder::GetFPGAIndex() const {
+  int32_t status = 0;
+  int val = HAL_GetEncoderFPGAIndex(m_encoder, &status);
+  wpi_setHALError(status);
+  return val;
+}
+
+void Encoder::InitSendable(SendableBuilder& builder) {
+  int32_t status = 0;
+  HAL_EncoderEncodingType type = HAL_GetEncoderEncodingType(m_encoder, &status);
+  wpi_setHALError(status);
+  if (type == HAL_EncoderEncodingType::HAL_Encoder_k4X)
+    builder.SetSmartDashboardType("Quadrature Encoder");
+  else
+    builder.SetSmartDashboardType("Encoder");
+
+  builder.AddDoubleProperty("Speed", [=]() { return GetRate(); }, nullptr);
+  builder.AddDoubleProperty("Distance", [=]() { return GetDistance(); },
+                            nullptr);
+  builder.AddDoubleProperty("Distance per Tick",
+                            [=]() { return GetDistancePerPulse(); }, nullptr);
+}
+
+void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) {
+  int32_t status = 0;
+  m_encoder = HAL_InitializeEncoder(
+      m_aSource->GetPortHandleForRouting(),
+      (HAL_AnalogTriggerType)m_aSource->GetAnalogTriggerTypeForRouting(),
+      m_bSource->GetPortHandleForRouting(),
+      (HAL_AnalogTriggerType)m_bSource->GetAnalogTriggerTypeForRouting(),
+      reverseDirection, (HAL_EncoderEncodingType)encodingType, &status);
+  wpi_setHALError(status);
+
+  HAL_Report(HALUsageReporting::kResourceType_Encoder, GetFPGAIndex() + 1,
+             encodingType);
+  SendableRegistry::GetInstance().AddLW(this, "Encoder",
+                                        m_aSource->GetChannel());
+}
+
+double Encoder::DecodingScaleFactor() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double val = HAL_GetEncoderDecodingScaleFactor(m_encoder, &status);
+  wpi_setHALError(status);
+  return val;
+}
diff --git a/wpilibc/src/main/native/cpp/Error.cpp b/wpilibc/src/main/native/cpp/Error.cpp
new file mode 100644
index 0000000..ee7dcbd
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Error.cpp
@@ -0,0 +1,99 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Error.h"
+
+#include <wpi/Path.h>
+#include <wpi/StackTrace.h>
+
+#include "frc/DriverStation.h"
+#include "frc/Timer.h"
+#include "frc/Utility.h"
+
+using namespace frc;
+
+Error::Error(Code code, const wpi::Twine& contextMessage,
+             wpi::StringRef filename, wpi::StringRef function, int lineNumber,
+             const ErrorBase* originatingObject) {
+  Set(code, contextMessage, filename, function, lineNumber, originatingObject);
+}
+
+bool Error::operator<(const Error& rhs) const {
+  if (m_code < rhs.m_code) {
+    return true;
+  } else if (m_message < rhs.m_message) {
+    return true;
+  } else if (m_filename < rhs.m_filename) {
+    return true;
+  } else if (m_function < rhs.m_function) {
+    return true;
+  } else if (m_lineNumber < rhs.m_lineNumber) {
+    return true;
+  } else if (m_originatingObject < rhs.m_originatingObject) {
+    return true;
+  } else if (m_timestamp < rhs.m_timestamp) {
+    return true;
+  } else {
+    return false;
+  }
+}
+
+Error::Code Error::GetCode() const { return m_code; }
+
+std::string Error::GetMessage() const { return m_message; }
+
+std::string Error::GetFilename() const { return m_filename; }
+
+std::string Error::GetFunction() const { return m_function; }
+
+int Error::GetLineNumber() const { return m_lineNumber; }
+
+const ErrorBase* Error::GetOriginatingObject() const {
+  return m_originatingObject;
+}
+
+double Error::GetTimestamp() const { return m_timestamp; }
+
+void Error::Set(Code code, const wpi::Twine& contextMessage,
+                wpi::StringRef filename, wpi::StringRef function,
+                int lineNumber, const ErrorBase* originatingObject) {
+  bool report = true;
+
+  if (code == m_code && GetTime() - m_timestamp < 1) {
+    report = false;
+  }
+
+  m_code = code;
+  m_message = contextMessage.str();
+  m_filename = filename;
+  m_function = function;
+  m_lineNumber = lineNumber;
+  m_originatingObject = originatingObject;
+
+  if (report) {
+    m_timestamp = GetTime();
+    Report();
+  }
+}
+
+void Error::Report() {
+  DriverStation::ReportError(
+      true, m_code, m_message,
+      m_function + wpi::Twine(" [") + wpi::sys::path::filename(m_filename) +
+          wpi::Twine(':') + wpi::Twine(m_lineNumber) + wpi::Twine(']'),
+      wpi::GetStackTrace(4));
+}
+
+void Error::Clear() {
+  m_code = 0;
+  m_message = "";
+  m_filename = "";
+  m_function = "";
+  m_lineNumber = 0;
+  m_originatingObject = nullptr;
+  m_timestamp = 0.0;
+}
diff --git a/wpilibc/src/main/native/cpp/ErrorBase.cpp b/wpilibc/src/main/native/cpp/ErrorBase.cpp
new file mode 100644
index 0000000..d098c07
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/ErrorBase.cpp
@@ -0,0 +1,187 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/ErrorBase.h"
+
+#include <cerrno>
+#include <cstdio>
+#include <cstring>
+#include <set>
+
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+#include <wpi/Format.h>
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+namespace {
+struct GlobalErrors {
+  wpi::mutex mutex;
+  std::set<Error> errors;
+  const Error* lastError{nullptr};
+
+  static GlobalErrors& GetInstance();
+  static void Insert(const Error& error);
+  static void Insert(Error&& error);
+};
+}  // namespace
+
+GlobalErrors& GlobalErrors::GetInstance() {
+  static GlobalErrors inst;
+  return inst;
+}
+
+void GlobalErrors::Insert(const Error& error) {
+  GlobalErrors& inst = GetInstance();
+  std::scoped_lock lock(inst.mutex);
+  inst.lastError = &(*inst.errors.insert(error).first);
+}
+
+void GlobalErrors::Insert(Error&& error) {
+  GlobalErrors& inst = GetInstance();
+  std::scoped_lock lock(inst.mutex);
+  inst.lastError = &(*inst.errors.insert(std::move(error)).first);
+}
+
+ErrorBase::ErrorBase() { HAL_Initialize(500, 0); }
+
+Error& ErrorBase::GetError() { return m_error; }
+
+const Error& ErrorBase::GetError() const { return m_error; }
+
+void ErrorBase::ClearError() const { m_error.Clear(); }
+
+void ErrorBase::SetErrnoError(const wpi::Twine& contextMessage,
+                              wpi::StringRef filename, wpi::StringRef function,
+                              int lineNumber) const {
+  wpi::SmallString<128> buf;
+  wpi::raw_svector_ostream err(buf);
+  int errNo = errno;
+  if (errNo == 0) {
+    err << "OK: ";
+  } else {
+    err << std::strerror(errNo) << " (" << wpi::format_hex(errNo, 10, true)
+        << "): ";
+  }
+
+  // Set the current error information for this object.
+  m_error.Set(-1, err.str() + contextMessage, filename, function, lineNumber,
+              this);
+
+  // Update the global error if there is not one already set.
+  GlobalErrors::Insert(m_error);
+}
+
+void ErrorBase::SetImaqError(int success, const wpi::Twine& contextMessage,
+                             wpi::StringRef filename, wpi::StringRef function,
+                             int lineNumber) const {
+  // If there was an error
+  if (success <= 0) {
+    // Set the current error information for this object.
+    m_error.Set(success, wpi::Twine(success) + ": " + contextMessage, filename,
+                function, lineNumber, this);
+
+    // Update the global error if there is not one already set.
+    GlobalErrors::Insert(m_error);
+  }
+}
+
+void ErrorBase::SetError(Error::Code code, const wpi::Twine& contextMessage,
+                         wpi::StringRef filename, wpi::StringRef function,
+                         int lineNumber) const {
+  //  If there was an error
+  if (code != 0) {
+    //  Set the current error information for this object.
+    m_error.Set(code, contextMessage, filename, function, lineNumber, this);
+
+    // Update the global error if there is not one already set.
+    GlobalErrors::Insert(m_error);
+  }
+}
+
+void ErrorBase::SetErrorRange(Error::Code code, int32_t minRange,
+                              int32_t maxRange, int32_t requestedValue,
+                              const wpi::Twine& contextMessage,
+                              wpi::StringRef filename, wpi::StringRef function,
+                              int lineNumber) const {
+  //  If there was an error
+  if (code != 0) {
+    //  Set the current error information for this object.
+    m_error.Set(code,
+                contextMessage + ", Minimum Value: " + wpi::Twine(minRange) +
+                    ", MaximumValue: " + wpi::Twine(maxRange) +
+                    ", Requested Value: " + wpi::Twine(requestedValue),
+                filename, function, lineNumber, this);
+
+    // Update the global error if there is not one already set.
+    GlobalErrors::Insert(m_error);
+  }
+}
+
+void ErrorBase::SetWPIError(const wpi::Twine& errorMessage, Error::Code code,
+                            const wpi::Twine& contextMessage,
+                            wpi::StringRef filename, wpi::StringRef function,
+                            int lineNumber) const {
+  //  Set the current error information for this object.
+  m_error.Set(code, errorMessage + ": " + contextMessage, filename, function,
+              lineNumber, this);
+
+  // Update the global error if there is not one already set.
+  GlobalErrors::Insert(m_error);
+}
+
+void ErrorBase::CloneError(const ErrorBase& rhs) const {
+  m_error = rhs.GetError();
+}
+
+bool ErrorBase::StatusIsFatal() const { return m_error.GetCode() < 0; }
+
+void ErrorBase::SetGlobalError(Error::Code code,
+                               const wpi::Twine& contextMessage,
+                               wpi::StringRef filename, wpi::StringRef function,
+                               int lineNumber) {
+  // If there was an error
+  if (code != 0) {
+    // Set the current error information for this object.
+    GlobalErrors::Insert(
+        Error(code, contextMessage, filename, function, lineNumber, nullptr));
+  }
+}
+
+void ErrorBase::SetGlobalWPIError(const wpi::Twine& errorMessage,
+                                  const wpi::Twine& contextMessage,
+                                  wpi::StringRef filename,
+                                  wpi::StringRef function, int lineNumber) {
+  GlobalErrors::Insert(Error(-1, errorMessage + ": " + contextMessage, filename,
+                             function, lineNumber, nullptr));
+}
+
+Error ErrorBase::GetGlobalError() {
+  auto& inst = GlobalErrors::GetInstance();
+  std::scoped_lock mutex(inst.mutex);
+  if (!inst.lastError) return Error{};
+  return *inst.lastError;
+}
+
+std::vector<Error> ErrorBase::GetGlobalErrors() {
+  auto& inst = GlobalErrors::GetInstance();
+  std::scoped_lock mutex(inst.mutex);
+  std::vector<Error> rv;
+  for (auto&& error : inst.errors) rv.push_back(error);
+  return rv;
+}
+
+void ErrorBase::ClearGlobalErrors() {
+  auto& inst = GlobalErrors::GetInstance();
+  std::scoped_lock mutex(inst.mutex);
+  inst.errors.clear();
+  inst.lastError = nullptr;
+}
diff --git a/wpilibc/src/main/native/cpp/Filesystem.cpp b/wpilibc/src/main/native/cpp/Filesystem.cpp
new file mode 100644
index 0000000..1546050
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Filesystem.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Filesystem.h"
+
+#include <wpi/FileSystem.h>
+#include <wpi/Path.h>
+
+#include "frc/RobotBase.h"
+
+void frc::filesystem::GetLaunchDirectory(wpi::SmallVectorImpl<char>& result) {
+  wpi::sys::fs::current_path(result);
+}
+
+void frc::filesystem::GetOperatingDirectory(
+    wpi::SmallVectorImpl<char>& result) {
+  if (RobotBase::IsReal()) {
+    wpi::sys::path::native("/home/lvuser", result);
+  } else {
+    frc::filesystem::GetLaunchDirectory(result);
+  }
+}
+
+void frc::filesystem::GetDeployDirectory(wpi::SmallVectorImpl<char>& result) {
+  frc::filesystem::GetOperatingDirectory(result);
+  wpi::sys::path::append(result, "deploy");
+}
diff --git a/wpilibc/src/main/native/cpp/GearTooth.cpp b/wpilibc/src/main/native/cpp/GearTooth.cpp
new file mode 100644
index 0000000..5fb5021
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/GearTooth.cpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/GearTooth.h"
+
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+constexpr double GearTooth::kGearToothThreshold;
+
+GearTooth::GearTooth(int channel, bool directionSensitive) : Counter(channel) {
+  EnableDirectionSensing(directionSensitive);
+  SendableRegistry::GetInstance().SetName(this, "GearTooth", channel);
+}
+
+GearTooth::GearTooth(DigitalSource* source, bool directionSensitive)
+    : Counter(source) {
+  EnableDirectionSensing(directionSensitive);
+  SendableRegistry::GetInstance().SetName(this, "GearTooth",
+                                          source->GetChannel());
+}
+
+GearTooth::GearTooth(std::shared_ptr<DigitalSource> source,
+                     bool directionSensitive)
+    : Counter(source) {
+  EnableDirectionSensing(directionSensitive);
+  SendableRegistry::GetInstance().SetName(this, "GearTooth",
+                                          source->GetChannel());
+}
+
+void GearTooth::EnableDirectionSensing(bool directionSensitive) {
+  if (directionSensitive) {
+    SetPulseLengthMode(kGearToothThreshold);
+  }
+}
+
+void GearTooth::InitSendable(SendableBuilder& builder) {
+  Counter::InitSendable(builder);
+  builder.SetSmartDashboardType("Gear Tooth");
+}
diff --git a/wpilibc/src/main/native/cpp/GenericHID.cpp b/wpilibc/src/main/native/cpp/GenericHID.cpp
new file mode 100644
index 0000000..a7dcfc0
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/GenericHID.cpp
@@ -0,0 +1,88 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/GenericHID.h"
+
+#include <hal/DriverStation.h>
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/DriverStation.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+GenericHID::GenericHID(int port) : m_ds(&DriverStation::GetInstance()) {
+  if (port >= DriverStation::kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+  }
+  m_port = port;
+}
+
+bool GenericHID::GetRawButton(int button) const {
+  return m_ds->GetStickButton(m_port, button);
+}
+
+bool GenericHID::GetRawButtonPressed(int button) {
+  return m_ds->GetStickButtonPressed(m_port, button);
+}
+
+bool GenericHID::GetRawButtonReleased(int button) {
+  return m_ds->GetStickButtonReleased(m_port, button);
+}
+
+double GenericHID::GetRawAxis(int axis) const {
+  return m_ds->GetStickAxis(m_port, axis);
+}
+
+int GenericHID::GetPOV(int pov) const { return m_ds->GetStickPOV(m_port, pov); }
+
+int GenericHID::GetAxisCount() const { return m_ds->GetStickAxisCount(m_port); }
+
+int GenericHID::GetPOVCount() const { return m_ds->GetStickPOVCount(m_port); }
+
+int GenericHID::GetButtonCount() const {
+  return m_ds->GetStickButtonCount(m_port);
+}
+
+GenericHID::HIDType GenericHID::GetType() const {
+  return static_cast<HIDType>(m_ds->GetJoystickType(m_port));
+}
+
+std::string GenericHID::GetName() const {
+  return m_ds->GetJoystickName(m_port);
+}
+
+int GenericHID::GetAxisType(int axis) const {
+  return m_ds->GetJoystickAxisType(m_port, axis);
+}
+
+int GenericHID::GetPort() const { return m_port; }
+
+void GenericHID::SetOutput(int outputNumber, bool value) {
+  m_outputs =
+      (m_outputs & ~(1 << (outputNumber - 1))) | (value << (outputNumber - 1));
+
+  HAL_SetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
+}
+
+void GenericHID::SetOutputs(int value) {
+  m_outputs = value;
+  HAL_SetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
+}
+
+void GenericHID::SetRumble(RumbleType type, double value) {
+  if (value < 0)
+    value = 0;
+  else if (value > 1)
+    value = 1;
+  if (type == kLeftRumble) {
+    m_leftRumble = value * 65535;
+  } else {
+    m_rightRumble = value * 65535;
+  }
+  HAL_SetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
+}
diff --git a/wpilibc/src/main/native/cpp/GyroBase.cpp b/wpilibc/src/main/native/cpp/GyroBase.cpp
new file mode 100644
index 0000000..ec67675
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/GyroBase.cpp
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/GyroBase.h"
+
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+double GyroBase::PIDGet() {
+  switch (GetPIDSourceType()) {
+    case PIDSourceType::kRate:
+      return GetRate();
+    case PIDSourceType::kDisplacement:
+      return GetAngle();
+    default:
+      return 0;
+  }
+}
+
+void GyroBase::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Gyro");
+  builder.AddDoubleProperty("Value", [=]() { return GetAngle(); }, nullptr);
+}
diff --git a/wpilibc/src/main/native/cpp/I2C.cpp b/wpilibc/src/main/native/cpp/I2C.cpp
new file mode 100644
index 0000000..21d92f2
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/I2C.cpp
@@ -0,0 +1,96 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/I2C.h"
+
+#include <utility>
+
+#include <hal/FRCUsageReporting.h>
+#include <hal/I2C.h>
+
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+I2C::I2C(Port port, int deviceAddress)
+    : m_port(static_cast<HAL_I2CPort>(port)), m_deviceAddress(deviceAddress) {
+  int32_t status = 0;
+  HAL_InitializeI2C(m_port, &status);
+  // wpi_setHALError(status);
+
+  HAL_Report(HALUsageReporting::kResourceType_I2C, deviceAddress);
+}
+
+I2C::~I2C() { HAL_CloseI2C(m_port); }
+
+bool I2C::Transaction(uint8_t* dataToSend, int sendSize, uint8_t* dataReceived,
+                      int receiveSize) {
+  int32_t status = 0;
+  status = HAL_TransactionI2C(m_port, m_deviceAddress, dataToSend, sendSize,
+                              dataReceived, receiveSize);
+  // wpi_setHALError(status);
+  return status < 0;
+}
+
+bool I2C::AddressOnly() { return Transaction(nullptr, 0, nullptr, 0); }
+
+bool I2C::Write(int registerAddress, uint8_t data) {
+  uint8_t buffer[2];
+  buffer[0] = registerAddress;
+  buffer[1] = data;
+  int32_t status = 0;
+  status = HAL_WriteI2C(m_port, m_deviceAddress, buffer, sizeof(buffer));
+  return status < 0;
+}
+
+bool I2C::WriteBulk(uint8_t* data, int count) {
+  int32_t status = 0;
+  status = HAL_WriteI2C(m_port, m_deviceAddress, data, count);
+  return status < 0;
+}
+
+bool I2C::Read(int registerAddress, int count, uint8_t* buffer) {
+  if (count < 1) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange, "count");
+    return true;
+  }
+  if (buffer == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "buffer");
+    return true;
+  }
+  uint8_t regAddr = registerAddress;
+  return Transaction(&regAddr, sizeof(regAddr), buffer, count);
+}
+
+bool I2C::ReadOnly(int count, uint8_t* buffer) {
+  if (count < 1) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange, "count");
+    return true;
+  }
+  if (buffer == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "buffer");
+    return true;
+  }
+  return HAL_ReadI2C(m_port, m_deviceAddress, buffer, count) < 0;
+}
+
+bool I2C::VerifySensor(int registerAddress, int count,
+                       const uint8_t* expected) {
+  // TODO: Make use of all 7 read bytes
+  uint8_t deviceData[4];
+  for (int i = 0, curRegisterAddress = registerAddress; i < count;
+       i += 4, curRegisterAddress += 4) {
+    int toRead = count - i < 4 ? count - i : 4;
+    // Read the chunk of data.  Return false if the sensor does not respond.
+    if (Read(curRegisterAddress, toRead, deviceData)) return false;
+
+    for (int j = 0; j < toRead; j++) {
+      if (deviceData[j] != expected[i + j]) return false;
+    }
+  }
+  return true;
+}
diff --git a/wpilibc/src/main/native/cpp/InterruptableSensorBase.cpp b/wpilibc/src/main/native/cpp/InterruptableSensorBase.cpp
new file mode 100644
index 0000000..202c61d
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/InterruptableSensorBase.cpp
@@ -0,0 +1,176 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/InterruptableSensorBase.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+InterruptableSensorBase::~InterruptableSensorBase() {
+  if (m_interrupt == HAL_kInvalidHandle) return;
+  int32_t status = 0;
+  HAL_CleanInterrupts(m_interrupt, &status);
+  // Ignore status, as an invalid handle just needs to be ignored.
+}
+
+void InterruptableSensorBase::RequestInterrupts(
+    HAL_InterruptHandlerFunction handler, void* param) {
+  if (StatusIsFatal()) return;
+
+  wpi_assert(m_interrupt == HAL_kInvalidHandle);
+  AllocateInterrupts(false);
+  if (StatusIsFatal()) return;  // if allocate failed, out of interrupts
+
+  int32_t status = 0;
+  HAL_RequestInterrupts(
+      m_interrupt, GetPortHandleForRouting(),
+      static_cast<HAL_AnalogTriggerType>(GetAnalogTriggerTypeForRouting()),
+      &status);
+  SetUpSourceEdge(true, false);
+  HAL_AttachInterruptHandler(m_interrupt, handler, param, &status);
+  wpi_setHALError(status);
+}
+
+void InterruptableSensorBase::RequestInterrupts(InterruptEventHandler handler) {
+  if (StatusIsFatal()) return;
+
+  wpi_assert(m_interrupt == HAL_kInvalidHandle);
+  AllocateInterrupts(false);
+  if (StatusIsFatal()) return;  // if allocate failed, out of interrupts
+
+  m_interruptHandler =
+      std::make_unique<InterruptEventHandler>(std::move(handler));
+
+  int32_t status = 0;
+  HAL_RequestInterrupts(
+      m_interrupt, GetPortHandleForRouting(),
+      static_cast<HAL_AnalogTriggerType>(GetAnalogTriggerTypeForRouting()),
+      &status);
+  SetUpSourceEdge(true, false);
+  HAL_AttachInterruptHandler(
+      m_interrupt,
+      [](uint32_t mask, void* param) {
+        auto self = reinterpret_cast<InterruptEventHandler*>(param);
+        // Rising edge result is the interrupt bit set in the byte 0xFF
+        // Falling edge result is the interrupt bit set in the byte 0xFF00
+        // Set any bit set to be true for that edge, and AND the 2 results
+        // together to match the existing enum for all interrupts
+        int32_t rising = (mask & 0xFF) ? 0x1 : 0x0;
+        int32_t falling = ((mask & 0xFF00) ? 0x0100 : 0x0);
+        WaitResult res = static_cast<WaitResult>(falling | rising);
+        (*self)(res);
+      },
+      m_interruptHandler.get(), &status);
+  wpi_setHALError(status);
+}
+
+void InterruptableSensorBase::RequestInterrupts() {
+  if (StatusIsFatal()) return;
+
+  wpi_assert(m_interrupt == HAL_kInvalidHandle);
+  AllocateInterrupts(true);
+  if (StatusIsFatal()) return;  // if allocate failed, out of interrupts
+
+  int32_t status = 0;
+  HAL_RequestInterrupts(
+      m_interrupt, GetPortHandleForRouting(),
+      static_cast<HAL_AnalogTriggerType>(GetAnalogTriggerTypeForRouting()),
+      &status);
+  wpi_setHALError(status);
+  SetUpSourceEdge(true, false);
+}
+
+void InterruptableSensorBase::CancelInterrupts() {
+  if (StatusIsFatal()) return;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  HAL_CleanInterrupts(m_interrupt, &status);
+  // Ignore status, as an invalid handle just needs to be ignored.
+  m_interrupt = HAL_kInvalidHandle;
+  m_interruptHandler = nullptr;
+}
+
+InterruptableSensorBase::WaitResult InterruptableSensorBase::WaitForInterrupt(
+    double timeout, bool ignorePrevious) {
+  if (StatusIsFatal()) return InterruptableSensorBase::kTimeout;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  int result;
+
+  result = HAL_WaitForInterrupt(m_interrupt, timeout, ignorePrevious, &status);
+  wpi_setHALError(status);
+
+  // Rising edge result is the interrupt bit set in the byte 0xFF
+  // Falling edge result is the interrupt bit set in the byte 0xFF00
+  // Set any bit set to be true for that edge, and AND the 2 results
+  // together to match the existing enum for all interrupts
+  int32_t rising = (result & 0xFF) ? 0x1 : 0x0;
+  int32_t falling = ((result & 0xFF00) ? 0x0100 : 0x0);
+  return static_cast<WaitResult>(falling | rising);
+}
+
+void InterruptableSensorBase::EnableInterrupts() {
+  if (StatusIsFatal()) return;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  HAL_EnableInterrupts(m_interrupt, &status);
+  wpi_setHALError(status);
+}
+
+void InterruptableSensorBase::DisableInterrupts() {
+  if (StatusIsFatal()) return;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  HAL_DisableInterrupts(m_interrupt, &status);
+  wpi_setHALError(status);
+}
+
+double InterruptableSensorBase::ReadRisingTimestamp() {
+  if (StatusIsFatal()) return 0.0;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  int64_t timestamp = HAL_ReadInterruptRisingTimestamp(m_interrupt, &status);
+  wpi_setHALError(status);
+  return timestamp * 1e-6;
+}
+
+double InterruptableSensorBase::ReadFallingTimestamp() {
+  if (StatusIsFatal()) return 0.0;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  int64_t timestamp = HAL_ReadInterruptFallingTimestamp(m_interrupt, &status);
+  wpi_setHALError(status);
+  return timestamp * 1e-6;
+}
+
+void InterruptableSensorBase::SetUpSourceEdge(bool risingEdge,
+                                              bool fallingEdge) {
+  if (StatusIsFatal()) return;
+  if (m_interrupt == HAL_kInvalidHandle) {
+    wpi_setWPIErrorWithContext(
+        NullParameter,
+        "You must call RequestInterrupts before SetUpSourceEdge");
+    return;
+  }
+  if (m_interrupt != HAL_kInvalidHandle) {
+    int32_t status = 0;
+    HAL_SetInterruptUpSourceEdge(m_interrupt, risingEdge, fallingEdge, &status);
+    wpi_setHALError(status);
+  }
+}
+
+void InterruptableSensorBase::AllocateInterrupts(bool watcher) {
+  wpi_assert(m_interrupt == HAL_kInvalidHandle);
+  // Expects the calling leaf class to allocate an interrupt index.
+  int32_t status = 0;
+  m_interrupt = HAL_InitializeInterrupts(watcher, &status);
+  wpi_setHALError(status);
+}
diff --git a/wpilibc/src/main/native/cpp/IterativeRobot.cpp b/wpilibc/src/main/native/cpp/IterativeRobot.cpp
new file mode 100644
index 0000000..c8664a5
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/IterativeRobot.cpp
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/IterativeRobot.h"
+
+#include <hal/DriverStation.h>
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/DriverStation.h"
+
+using namespace frc;
+
+static constexpr auto kPacketPeriod = 0.02_s;
+
+IterativeRobot::IterativeRobot() : IterativeRobotBase(kPacketPeriod) {
+  HAL_Report(HALUsageReporting::kResourceType_Framework,
+             HALUsageReporting::kFramework_Iterative);
+}
+
+void IterativeRobot::StartCompetition() {
+  RobotInit();
+
+  // Tell the DS that the robot is ready to be enabled
+  HAL_ObserveUserProgramStarting();
+
+  // Loop forever, calling the appropriate mode-dependent function
+  while (true) {
+    // Wait for driver station data so the loop doesn't hog the CPU
+    DriverStation::GetInstance().WaitForData();
+    if (m_exit) break;
+
+    LoopFunc();
+  }
+}
+
+void IterativeRobot::EndCompetition() {
+  m_exit = true;
+  DriverStation::GetInstance().WakeupWaitForData();
+}
diff --git a/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp b/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp
new file mode 100644
index 0000000..2997234
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp
@@ -0,0 +1,180 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/IterativeRobotBase.h"
+
+#include <cstdio>
+
+#include <hal/DriverStation.h>
+#include <hal/FRCUsageReporting.h>
+#include <wpi/Format.h>
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/DriverStation.h"
+#include "frc/Timer.h"
+#include "frc/livewindow/LiveWindow.h"
+#include "frc/shuffleboard/Shuffleboard.h"
+#include "frc/smartdashboard/SmartDashboard.h"
+
+using namespace frc;
+
+IterativeRobotBase::IterativeRobotBase(double period)
+    : IterativeRobotBase(units::second_t(period)) {}
+
+IterativeRobotBase::IterativeRobotBase(units::second_t period)
+    : m_period(period),
+      m_watchdog(period, [this] { PrintLoopOverrunMessage(); }) {}
+
+void IterativeRobotBase::RobotInit() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
+}
+
+void IterativeRobotBase::DisabledInit() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
+}
+
+void IterativeRobotBase::AutonomousInit() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
+}
+
+void IterativeRobotBase::TeleopInit() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
+}
+
+void IterativeRobotBase::TestInit() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
+}
+
+void IterativeRobotBase::RobotPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
+    firstRun = false;
+  }
+}
+
+void IterativeRobotBase::DisabledPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
+    firstRun = false;
+  }
+}
+
+void IterativeRobotBase::AutonomousPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
+    firstRun = false;
+  }
+}
+
+void IterativeRobotBase::TeleopPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
+    firstRun = false;
+  }
+}
+
+void IterativeRobotBase::TestPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    wpi::outs() << "Default " << __FUNCTION__ << "() method... Override me!\n";
+    firstRun = false;
+  }
+}
+
+void IterativeRobotBase::LoopFunc() {
+  m_watchdog.Reset();
+
+  // Call the appropriate function depending upon the current robot mode
+  if (IsDisabled()) {
+    // Call DisabledInit() if we are now just entering disabled mode from
+    // either a different mode or from power-on.
+    if (m_lastMode != Mode::kDisabled) {
+      LiveWindow::GetInstance()->SetEnabled(false);
+      Shuffleboard::DisableActuatorWidgets();
+      DisabledInit();
+      m_watchdog.AddEpoch("DisabledInit()");
+      m_lastMode = Mode::kDisabled;
+    }
+
+    HAL_ObserveUserProgramDisabled();
+    DisabledPeriodic();
+    m_watchdog.AddEpoch("DisabledPeriodic()");
+  } else if (IsAutonomous()) {
+    // Call AutonomousInit() if we are now just entering autonomous mode from
+    // either a different mode or from power-on.
+    if (m_lastMode != Mode::kAutonomous) {
+      LiveWindow::GetInstance()->SetEnabled(false);
+      Shuffleboard::DisableActuatorWidgets();
+      AutonomousInit();
+      m_watchdog.AddEpoch("AutonomousInit()");
+      m_lastMode = Mode::kAutonomous;
+    }
+
+    HAL_ObserveUserProgramAutonomous();
+    AutonomousPeriodic();
+    m_watchdog.AddEpoch("AutonomousPeriodic()");
+  } else if (IsOperatorControl()) {
+    // Call TeleopInit() if we are now just entering teleop mode from
+    // either a different mode or from power-on.
+    if (m_lastMode != Mode::kTeleop) {
+      LiveWindow::GetInstance()->SetEnabled(false);
+      Shuffleboard::DisableActuatorWidgets();
+      TeleopInit();
+      m_watchdog.AddEpoch("TeleopInit()");
+      m_lastMode = Mode::kTeleop;
+    }
+
+    HAL_ObserveUserProgramTeleop();
+    TeleopPeriodic();
+    m_watchdog.AddEpoch("TeleopPeriodic()");
+  } else {
+    // Call TestInit() if we are now just entering test mode from
+    // either a different mode or from power-on.
+    if (m_lastMode != Mode::kTest) {
+      LiveWindow::GetInstance()->SetEnabled(true);
+      Shuffleboard::EnableActuatorWidgets();
+      TestInit();
+      m_watchdog.AddEpoch("TestInit()");
+      m_lastMode = Mode::kTest;
+    }
+
+    HAL_ObserveUserProgramTest();
+    TestPeriodic();
+    m_watchdog.AddEpoch("TestPeriodic()");
+  }
+
+  RobotPeriodic();
+  m_watchdog.AddEpoch("RobotPeriodic()");
+
+  SmartDashboard::UpdateValues();
+  m_watchdog.AddEpoch("SmartDashboard::UpdateValues()");
+  LiveWindow::GetInstance()->UpdateValues();
+  m_watchdog.AddEpoch("LiveWindow::UpdateValues()");
+  Shuffleboard::Update();
+  m_watchdog.AddEpoch("Shuffleboard::Update()");
+  m_watchdog.Disable();
+
+  // Warn on loop time overruns
+  if (m_watchdog.IsExpired()) {
+    m_watchdog.PrintEpochs();
+  }
+}
+
+void IterativeRobotBase::PrintLoopOverrunMessage() {
+  wpi::SmallString<128> str;
+  wpi::raw_svector_ostream buf(str);
+
+  buf << "Loop time of " << wpi::format("%.6f", m_period.to<double>())
+      << "s overrun\n";
+
+  DriverStation::ReportWarning(str);
+}
diff --git a/wpilibc/src/main/native/cpp/Jaguar.cpp b/wpilibc/src/main/native/cpp/Jaguar.cpp
new file mode 100644
index 0000000..c87e4d1
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Jaguar.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Jaguar.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+Jaguar::Jaguar(int channel) : PWMSpeedController(channel) {
+  SetBounds(2.31, 1.55, 1.507, 1.454, 0.697);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_Jaguar, GetChannel() + 1);
+  SendableRegistry::GetInstance().SetName(this, "Jaguar", GetChannel());
+}
diff --git a/wpilibc/src/main/native/cpp/Joystick.cpp b/wpilibc/src/main/native/cpp/Joystick.cpp
new file mode 100644
index 0000000..8d464cf
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Joystick.cpp
@@ -0,0 +1,94 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Joystick.h"
+
+#include <cmath>
+
+#include <hal/FRCUsageReporting.h>
+#include <wpi/math>
+
+#include "frc/DriverStation.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+Joystick::Joystick(int port) : GenericHID(port) {
+  m_axes[Axis::kX] = kDefaultXChannel;
+  m_axes[Axis::kY] = kDefaultYChannel;
+  m_axes[Axis::kZ] = kDefaultZChannel;
+  m_axes[Axis::kTwist] = kDefaultTwistChannel;
+  m_axes[Axis::kThrottle] = kDefaultThrottleChannel;
+
+  HAL_Report(HALUsageReporting::kResourceType_Joystick, port + 1);
+}
+
+void Joystick::SetXChannel(int channel) { m_axes[Axis::kX] = channel; }
+
+void Joystick::SetYChannel(int channel) { m_axes[Axis::kY] = channel; }
+
+void Joystick::SetZChannel(int channel) { m_axes[Axis::kZ] = channel; }
+
+void Joystick::SetTwistChannel(int channel) { m_axes[Axis::kTwist] = channel; }
+
+void Joystick::SetThrottleChannel(int channel) {
+  m_axes[Axis::kThrottle] = channel;
+}
+
+int Joystick::GetXChannel() const { return m_axes[Axis::kX]; }
+
+int Joystick::GetYChannel() const { return m_axes[Axis::kY]; }
+
+int Joystick::GetZChannel() const { return m_axes[Axis::kZ]; }
+
+int Joystick::GetTwistChannel() const { return m_axes[Axis::kTwist]; }
+
+int Joystick::GetThrottleChannel() const { return m_axes[Axis::kThrottle]; }
+
+double Joystick::GetX(JoystickHand hand) const {
+  return GetRawAxis(m_axes[Axis::kX]);
+}
+
+double Joystick::GetY(JoystickHand hand) const {
+  return GetRawAxis(m_axes[Axis::kY]);
+}
+
+double Joystick::GetZ() const { return GetRawAxis(m_axes[Axis::kZ]); }
+
+double Joystick::GetTwist() const { return GetRawAxis(m_axes[Axis::kTwist]); }
+
+double Joystick::GetThrottle() const {
+  return GetRawAxis(m_axes[Axis::kThrottle]);
+}
+
+bool Joystick::GetTrigger() const { return GetRawButton(Button::kTrigger); }
+
+bool Joystick::GetTriggerPressed() {
+  return GetRawButtonPressed(Button::kTrigger);
+}
+
+bool Joystick::GetTriggerReleased() {
+  return GetRawButtonReleased(Button::kTrigger);
+}
+
+bool Joystick::GetTop() const { return GetRawButton(Button::kTop); }
+
+bool Joystick::GetTopPressed() { return GetRawButtonPressed(Button::kTop); }
+
+bool Joystick::GetTopReleased() { return GetRawButtonReleased(Button::kTop); }
+
+double Joystick::GetMagnitude() const {
+  return std::sqrt(std::pow(GetX(), 2) + std::pow(GetY(), 2));
+}
+
+double Joystick::GetDirectionRadians() const {
+  return std::atan2(GetX(), -GetY());
+}
+
+double Joystick::GetDirectionDegrees() const {
+  return (180 / wpi::math::pi) * GetDirectionRadians();
+}
diff --git a/wpilibc/src/main/native/cpp/MotorSafety.cpp b/wpilibc/src/main/native/cpp/MotorSafety.cpp
new file mode 100644
index 0000000..1806e86
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/MotorSafety.cpp
@@ -0,0 +1,113 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/MotorSafety.h"
+
+#include <algorithm>
+#include <utility>
+
+#include <wpi/SmallPtrSet.h>
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/DriverStation.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+static wpi::SmallPtrSet<MotorSafety*, 32> instanceList;
+static wpi::mutex listMutex;
+
+MotorSafety::MotorSafety() {
+  std::scoped_lock lock(listMutex);
+  instanceList.insert(this);
+}
+
+MotorSafety::~MotorSafety() {
+  std::scoped_lock lock(listMutex);
+  instanceList.erase(this);
+}
+
+MotorSafety::MotorSafety(MotorSafety&& rhs)
+    : ErrorBase(std::move(rhs)),
+      m_expiration(std::move(rhs.m_expiration)),
+      m_enabled(std::move(rhs.m_enabled)),
+      m_stopTime(std::move(rhs.m_stopTime)) {}
+
+MotorSafety& MotorSafety::operator=(MotorSafety&& rhs) {
+  std::scoped_lock lock(m_thisMutex, rhs.m_thisMutex);
+
+  ErrorBase::operator=(std::move(rhs));
+
+  m_expiration = std::move(rhs.m_expiration);
+  m_enabled = std::move(rhs.m_enabled);
+  m_stopTime = std::move(rhs.m_stopTime);
+
+  return *this;
+}
+
+void MotorSafety::Feed() {
+  std::scoped_lock lock(m_thisMutex);
+  m_stopTime = Timer::GetFPGATimestamp() + m_expiration;
+}
+
+void MotorSafety::SetExpiration(double expirationTime) {
+  std::scoped_lock lock(m_thisMutex);
+  m_expiration = expirationTime;
+}
+
+double MotorSafety::GetExpiration() const {
+  std::scoped_lock lock(m_thisMutex);
+  return m_expiration;
+}
+
+bool MotorSafety::IsAlive() const {
+  std::scoped_lock lock(m_thisMutex);
+  return !m_enabled || m_stopTime > Timer::GetFPGATimestamp();
+}
+
+void MotorSafety::SetSafetyEnabled(bool enabled) {
+  std::scoped_lock lock(m_thisMutex);
+  m_enabled = enabled;
+}
+
+bool MotorSafety::IsSafetyEnabled() const {
+  std::scoped_lock lock(m_thisMutex);
+  return m_enabled;
+}
+
+void MotorSafety::Check() {
+  bool enabled;
+  double stopTime;
+
+  {
+    std::scoped_lock lock(m_thisMutex);
+    enabled = m_enabled;
+    stopTime = m_stopTime;
+  }
+
+  DriverStation& ds = DriverStation::GetInstance();
+  if (!enabled || ds.IsDisabled() || ds.IsTest()) {
+    return;
+  }
+
+  if (stopTime < Timer::GetFPGATimestamp()) {
+    wpi::SmallString<128> buf;
+    wpi::raw_svector_ostream desc(buf);
+    GetDescription(desc);
+    desc << "... Output not updated often enough.";
+    wpi_setWPIErrorWithContext(Timeout, desc.str());
+    StopMotor();
+  }
+}
+
+void MotorSafety::CheckMotors() {
+  std::scoped_lock lock(listMutex);
+  for (auto elem : instanceList) {
+    elem->Check();
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/NidecBrushless.cpp b/wpilibc/src/main/native/cpp/NidecBrushless.cpp
new file mode 100644
index 0000000..5bce36e
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/NidecBrushless.cpp
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/NidecBrushless.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel)
+    : m_dio(dioChannel), m_pwm(pwmChannel) {
+  auto& registry = SendableRegistry::GetInstance();
+  registry.AddChild(this, &m_dio);
+  registry.AddChild(this, &m_pwm);
+  SetExpiration(0.0);
+  SetSafetyEnabled(false);
+
+  // the dio controls the output (in PWM mode)
+  m_dio.SetPWMRate(15625);
+  m_dio.EnablePWM(0.5);
+
+  HAL_Report(HALUsageReporting::kResourceType_NidecBrushless, pwmChannel + 1);
+  registry.AddLW(this, "Nidec Brushless", pwmChannel);
+}
+
+void NidecBrushless::Set(double speed) {
+  if (!m_disabled) {
+    m_speed = speed;
+    m_dio.UpdateDutyCycle(0.5 + 0.5 * (m_isInverted ? -speed : speed));
+    m_pwm.SetRaw(0xffff);
+  }
+  Feed();
+}
+
+double NidecBrushless::Get() const { return m_speed; }
+
+void NidecBrushless::SetInverted(bool isInverted) { m_isInverted = isInverted; }
+
+bool NidecBrushless::GetInverted() const { return m_isInverted; }
+
+void NidecBrushless::Disable() {
+  m_disabled = true;
+  m_dio.UpdateDutyCycle(0.5);
+  m_pwm.SetDisabled();
+}
+
+void NidecBrushless::Enable() { m_disabled = false; }
+
+void NidecBrushless::PIDWrite(double output) { Set(output); }
+
+void NidecBrushless::StopMotor() {
+  m_dio.UpdateDutyCycle(0.5);
+  m_pwm.SetDisabled();
+}
+
+void NidecBrushless::GetDescription(wpi::raw_ostream& desc) const {
+  desc << "Nidec " << GetChannel();
+}
+
+int NidecBrushless::GetChannel() const { return m_pwm.GetChannel(); }
+
+void NidecBrushless::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Nidec Brushless");
+  builder.SetActuator(true);
+  builder.SetSafeState([=]() { StopMotor(); });
+  builder.AddDoubleProperty("Value", [=]() { return Get(); },
+                            [=](double value) { Set(value); });
+}
diff --git a/wpilibc/src/main/native/cpp/Notifier.cpp b/wpilibc/src/main/native/cpp/Notifier.cpp
new file mode 100644
index 0000000..a7fa038
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Notifier.cpp
@@ -0,0 +1,148 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Notifier.h"
+
+#include <utility>
+
+#include <hal/FRCUsageReporting.h>
+#include <hal/Notifier.h>
+#include <wpi/SmallString.h>
+
+#include "frc/Timer.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+Notifier::Notifier(std::function<void()> handler) {
+  if (handler == nullptr)
+    wpi_setWPIErrorWithContext(NullParameter, "handler must not be nullptr");
+  m_handler = handler;
+  int32_t status = 0;
+  m_notifier = HAL_InitializeNotifier(&status);
+  wpi_setHALError(status);
+
+  m_thread = std::thread([=] {
+    for (;;) {
+      int32_t status = 0;
+      HAL_NotifierHandle notifier = m_notifier.load();
+      if (notifier == 0) break;
+      uint64_t curTime = HAL_WaitForNotifierAlarm(notifier, &status);
+      if (curTime == 0 || status != 0) break;
+
+      std::function<void()> handler;
+      {
+        std::scoped_lock lock(m_processMutex);
+        handler = m_handler;
+        if (m_periodic) {
+          m_expirationTime += m_period;
+          UpdateAlarm();
+        } else {
+          // need to update the alarm to cause it to wait again
+          UpdateAlarm(UINT64_MAX);
+        }
+      }
+
+      // call callback
+      if (handler) handler();
+    }
+  });
+}
+
+Notifier::~Notifier() {
+  int32_t status = 0;
+  // atomically set handle to 0, then clean
+  HAL_NotifierHandle handle = m_notifier.exchange(0);
+  HAL_StopNotifier(handle, &status);
+  wpi_setHALError(status);
+
+  // Join the thread to ensure the handler has exited.
+  if (m_thread.joinable()) m_thread.join();
+
+  HAL_CleanNotifier(handle, &status);
+}
+
+Notifier::Notifier(Notifier&& rhs)
+    : ErrorBase(std::move(rhs)),
+      m_thread(std::move(rhs.m_thread)),
+      m_notifier(rhs.m_notifier.load()),
+      m_handler(std::move(rhs.m_handler)),
+      m_expirationTime(std::move(rhs.m_expirationTime)),
+      m_period(std::move(rhs.m_period)),
+      m_periodic(std::move(rhs.m_periodic)) {
+  rhs.m_notifier = HAL_kInvalidHandle;
+}
+
+Notifier& Notifier::operator=(Notifier&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+
+  m_thread = std::move(rhs.m_thread);
+  m_notifier = rhs.m_notifier.load();
+  rhs.m_notifier = HAL_kInvalidHandle;
+  m_handler = std::move(rhs.m_handler);
+  m_expirationTime = std::move(rhs.m_expirationTime);
+  m_period = std::move(rhs.m_period);
+  m_periodic = std::move(rhs.m_periodic);
+
+  return *this;
+}
+
+void Notifier::SetName(const wpi::Twine& name) {
+  wpi::SmallString<64> nameBuf;
+  int32_t status = 0;
+  HAL_SetNotifierName(m_notifier,
+                      name.toNullTerminatedStringRef(nameBuf).data(), &status);
+}
+
+void Notifier::SetHandler(std::function<void()> handler) {
+  std::scoped_lock lock(m_processMutex);
+  m_handler = handler;
+}
+
+void Notifier::StartSingle(double delay) {
+  StartSingle(units::second_t(delay));
+}
+
+void Notifier::StartSingle(units::second_t delay) {
+  std::scoped_lock lock(m_processMutex);
+  m_periodic = false;
+  m_period = delay.to<double>();
+  m_expirationTime = Timer::GetFPGATimestamp() + m_period;
+  UpdateAlarm();
+}
+
+void Notifier::StartPeriodic(double period) {
+  StartPeriodic(units::second_t(period));
+}
+
+void Notifier::StartPeriodic(units::second_t period) {
+  std::scoped_lock lock(m_processMutex);
+  m_periodic = true;
+  m_period = period.to<double>();
+  m_expirationTime = Timer::GetFPGATimestamp() + m_period;
+  UpdateAlarm();
+}
+
+void Notifier::Stop() {
+  int32_t status = 0;
+  HAL_CancelNotifierAlarm(m_notifier, &status);
+  wpi_setHALError(status);
+}
+
+void Notifier::UpdateAlarm(uint64_t triggerTime) {
+  int32_t status = 0;
+  // Return if we are being destructed, or were not created successfully
+  auto notifier = m_notifier.load();
+  if (notifier == 0) return;
+  HAL_UpdateNotifierAlarm(notifier, triggerTime, &status);
+  wpi_setHALError(status);
+}
+
+void Notifier::UpdateAlarm() {
+  UpdateAlarm(static_cast<uint64_t>(m_expirationTime * 1e6));
+}
diff --git a/wpilibc/src/main/native/cpp/PIDBase.cpp b/wpilibc/src/main/native/cpp/PIDBase.cpp
new file mode 100644
index 0000000..c8f6fed
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/PIDBase.cpp
@@ -0,0 +1,353 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/PIDBase.h"
+
+#include <algorithm>
+#include <cmath>
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/PIDOutput.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+template <class T>
+constexpr const T& clamp(const T& value, const T& low, const T& high) {
+  return std::max(low, std::min(value, high));
+}
+
+PIDBase::PIDBase(double Kp, double Ki, double Kd, PIDSource& source,
+                 PIDOutput& output)
+    : PIDBase(Kp, Ki, Kd, 0.0, source, output) {}
+
+PIDBase::PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource& source,
+                 PIDOutput& output) {
+  m_P = Kp;
+  m_I = Ki;
+  m_D = Kd;
+  m_F = Kf;
+
+  m_pidInput = &source;
+  m_filter = LinearFilter<double>::MovingAverage(1);
+
+  m_pidOutput = &output;
+
+  m_setpointTimer.Start();
+
+  static int instances = 0;
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_PIDController, instances);
+  SendableRegistry::GetInstance().Add(this, "PIDController", instances);
+}
+
+double PIDBase::Get() const {
+  std::scoped_lock lock(m_thisMutex);
+  return m_result;
+}
+
+void PIDBase::SetContinuous(bool continuous) {
+  std::scoped_lock lock(m_thisMutex);
+  m_continuous = continuous;
+}
+
+void PIDBase::SetInputRange(double minimumInput, double maximumInput) {
+  {
+    std::scoped_lock lock(m_thisMutex);
+    m_minimumInput = minimumInput;
+    m_maximumInput = maximumInput;
+    m_inputRange = maximumInput - minimumInput;
+  }
+
+  SetSetpoint(m_setpoint);
+}
+
+void PIDBase::SetOutputRange(double minimumOutput, double maximumOutput) {
+  std::scoped_lock lock(m_thisMutex);
+  m_minimumOutput = minimumOutput;
+  m_maximumOutput = maximumOutput;
+}
+
+void PIDBase::SetPID(double p, double i, double d) {
+  {
+    std::scoped_lock lock(m_thisMutex);
+    m_P = p;
+    m_I = i;
+    m_D = d;
+  }
+}
+
+void PIDBase::SetPID(double p, double i, double d, double f) {
+  std::scoped_lock lock(m_thisMutex);
+  m_P = p;
+  m_I = i;
+  m_D = d;
+  m_F = f;
+}
+
+void PIDBase::SetP(double p) {
+  std::scoped_lock lock(m_thisMutex);
+  m_P = p;
+}
+
+void PIDBase::SetI(double i) {
+  std::scoped_lock lock(m_thisMutex);
+  m_I = i;
+}
+
+void PIDBase::SetD(double d) {
+  std::scoped_lock lock(m_thisMutex);
+  m_D = d;
+}
+
+void PIDBase::SetF(double f) {
+  std::scoped_lock lock(m_thisMutex);
+  m_F = f;
+}
+
+double PIDBase::GetP() const {
+  std::scoped_lock lock(m_thisMutex);
+  return m_P;
+}
+
+double PIDBase::GetI() const {
+  std::scoped_lock lock(m_thisMutex);
+  return m_I;
+}
+
+double PIDBase::GetD() const {
+  std::scoped_lock lock(m_thisMutex);
+  return m_D;
+}
+
+double PIDBase::GetF() const {
+  std::scoped_lock lock(m_thisMutex);
+  return m_F;
+}
+
+void PIDBase::SetSetpoint(double setpoint) {
+  {
+    std::scoped_lock lock(m_thisMutex);
+
+    if (m_maximumInput > m_minimumInput) {
+      if (setpoint > m_maximumInput)
+        m_setpoint = m_maximumInput;
+      else if (setpoint < m_minimumInput)
+        m_setpoint = m_minimumInput;
+      else
+        m_setpoint = setpoint;
+    } else {
+      m_setpoint = setpoint;
+    }
+  }
+}
+
+double PIDBase::GetSetpoint() const {
+  std::scoped_lock lock(m_thisMutex);
+  return m_setpoint;
+}
+
+double PIDBase::GetDeltaSetpoint() const {
+  std::scoped_lock lock(m_thisMutex);
+  return (m_setpoint - m_prevSetpoint) / m_setpointTimer.Get();
+}
+
+double PIDBase::GetError() const {
+  double setpoint = GetSetpoint();
+  {
+    std::scoped_lock lock(m_thisMutex);
+    return GetContinuousError(setpoint - m_pidInput->PIDGet());
+  }
+}
+
+double PIDBase::GetAvgError() const { return GetError(); }
+
+void PIDBase::SetPIDSourceType(PIDSourceType pidSource) {
+  m_pidInput->SetPIDSourceType(pidSource);
+}
+
+PIDSourceType PIDBase::GetPIDSourceType() const {
+  return m_pidInput->GetPIDSourceType();
+}
+
+void PIDBase::SetTolerance(double percent) {
+  std::scoped_lock lock(m_thisMutex);
+  m_toleranceType = kPercentTolerance;
+  m_tolerance = percent;
+}
+
+void PIDBase::SetAbsoluteTolerance(double absTolerance) {
+  std::scoped_lock lock(m_thisMutex);
+  m_toleranceType = kAbsoluteTolerance;
+  m_tolerance = absTolerance;
+}
+
+void PIDBase::SetPercentTolerance(double percent) {
+  std::scoped_lock lock(m_thisMutex);
+  m_toleranceType = kPercentTolerance;
+  m_tolerance = percent;
+}
+
+void PIDBase::SetToleranceBuffer(int bufLength) {
+  std::scoped_lock lock(m_thisMutex);
+  m_filter = LinearFilter<double>::MovingAverage(bufLength);
+}
+
+bool PIDBase::OnTarget() const {
+  double error = GetError();
+
+  std::scoped_lock lock(m_thisMutex);
+  switch (m_toleranceType) {
+    case kPercentTolerance:
+      return std::fabs(error) < m_tolerance / 100 * m_inputRange;
+      break;
+    case kAbsoluteTolerance:
+      return std::fabs(error) < m_tolerance;
+      break;
+    case kNoTolerance:
+      // TODO: this case needs an error
+      return false;
+  }
+  return false;
+}
+
+void PIDBase::Reset() {
+  std::scoped_lock lock(m_thisMutex);
+  m_prevError = 0;
+  m_totalError = 0;
+  m_result = 0;
+}
+
+void PIDBase::PIDWrite(double output) { SetSetpoint(output); }
+
+void PIDBase::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("PIDController");
+  builder.SetSafeState([=]() { Reset(); });
+  builder.AddDoubleProperty("p", [=]() { return GetP(); },
+                            [=](double value) { SetP(value); });
+  builder.AddDoubleProperty("i", [=]() { return GetI(); },
+                            [=](double value) { SetI(value); });
+  builder.AddDoubleProperty("d", [=]() { return GetD(); },
+                            [=](double value) { SetD(value); });
+  builder.AddDoubleProperty("f", [=]() { return GetF(); },
+                            [=](double value) { SetF(value); });
+  builder.AddDoubleProperty("setpoint", [=]() { return GetSetpoint(); },
+                            [=](double value) { SetSetpoint(value); });
+}
+
+void PIDBase::Calculate() {
+  if (m_pidInput == nullptr || m_pidOutput == nullptr) return;
+
+  bool enabled;
+  {
+    std::scoped_lock lock(m_thisMutex);
+    enabled = m_enabled;
+  }
+
+  if (enabled) {
+    double input;
+
+    // Storage for function inputs
+    PIDSourceType pidSourceType;
+    double P;
+    double I;
+    double D;
+    double feedForward = CalculateFeedForward();
+    double minimumOutput;
+    double maximumOutput;
+
+    // Storage for function input-outputs
+    double prevError;
+    double error;
+    double totalError;
+
+    {
+      std::scoped_lock lock(m_thisMutex);
+
+      input = m_filter.Calculate(m_pidInput->PIDGet());
+
+      pidSourceType = m_pidInput->GetPIDSourceType();
+      P = m_P;
+      I = m_I;
+      D = m_D;
+      minimumOutput = m_minimumOutput;
+      maximumOutput = m_maximumOutput;
+
+      prevError = m_prevError;
+      error = GetContinuousError(m_setpoint - input);
+      totalError = m_totalError;
+    }
+
+    // Storage for function outputs
+    double result;
+
+    if (pidSourceType == PIDSourceType::kRate) {
+      if (P != 0) {
+        totalError =
+            clamp(totalError + error, minimumOutput / P, maximumOutput / P);
+      }
+
+      result = D * error + P * totalError + feedForward;
+    } else {
+      if (I != 0) {
+        totalError =
+            clamp(totalError + error, minimumOutput / I, maximumOutput / I);
+      }
+
+      result =
+          P * error + I * totalError + D * (error - prevError) + feedForward;
+    }
+
+    result = clamp(result, minimumOutput, maximumOutput);
+
+    {
+      // Ensures m_enabled check and PIDWrite() call occur atomically
+      std::scoped_lock pidWriteLock(m_pidWriteMutex);
+      std::unique_lock mainLock(m_thisMutex);
+      if (m_enabled) {
+        // Don't block other PIDBase operations on PIDWrite()
+        mainLock.unlock();
+
+        m_pidOutput->PIDWrite(result);
+      }
+    }
+
+    std::scoped_lock lock(m_thisMutex);
+    m_prevError = m_error;
+    m_error = error;
+    m_totalError = totalError;
+    m_result = result;
+  }
+}
+
+double PIDBase::CalculateFeedForward() {
+  if (m_pidInput->GetPIDSourceType() == PIDSourceType::kRate) {
+    return m_F * GetSetpoint();
+  } else {
+    double temp = m_F * GetDeltaSetpoint();
+    m_prevSetpoint = m_setpoint;
+    m_setpointTimer.Reset();
+    return temp;
+  }
+}
+
+double PIDBase::GetContinuousError(double error) const {
+  if (m_continuous && m_inputRange != 0) {
+    error = std::fmod(error, m_inputRange);
+    if (std::fabs(error) > m_inputRange / 2) {
+      if (error > 0) {
+        return error - m_inputRange;
+      } else {
+        return error + m_inputRange;
+      }
+    }
+  }
+
+  return error;
+}
diff --git a/wpilibc/src/main/native/cpp/PIDController.cpp b/wpilibc/src/main/native/cpp/PIDController.cpp
new file mode 100644
index 0000000..0c86f55
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/PIDController.cpp
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/PIDController.h"
+
+#include "frc/Notifier.h"
+#include "frc/PIDOutput.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource* source,
+                             PIDOutput* output, double period)
+    : PIDController(Kp, Ki, Kd, 0.0, *source, *output, period) {}
+
+PIDController::PIDController(double Kp, double Ki, double Kd, double Kf,
+                             PIDSource* source, PIDOutput* output,
+                             double period)
+    : PIDController(Kp, Ki, Kd, Kf, *source, *output, period) {}
+
+PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource& source,
+                             PIDOutput& output, double period)
+    : PIDController(Kp, Ki, Kd, 0.0, source, output, period) {}
+
+PIDController::PIDController(double Kp, double Ki, double Kd, double Kf,
+                             PIDSource& source, PIDOutput& output,
+                             double period)
+    : PIDBase(Kp, Ki, Kd, Kf, source, output) {
+  m_controlLoop = std::make_unique<Notifier>(&PIDController::Calculate, this);
+  m_controlLoop->StartPeriodic(units::second_t(period));
+}
+
+PIDController::~PIDController() {
+  // Forcefully stopping the notifier so the callback can successfully run.
+  m_controlLoop->Stop();
+}
+
+void PIDController::Enable() {
+  {
+    std::scoped_lock lock(m_thisMutex);
+    m_enabled = true;
+  }
+}
+
+void PIDController::Disable() {
+  {
+    // Ensures m_enabled modification and PIDWrite() call occur atomically
+    std::scoped_lock pidWriteLock(m_pidWriteMutex);
+    {
+      std::scoped_lock mainLock(m_thisMutex);
+      m_enabled = false;
+    }
+
+    m_pidOutput->PIDWrite(0);
+  }
+}
+
+void PIDController::SetEnabled(bool enable) {
+  if (enable) {
+    Enable();
+  } else {
+    Disable();
+  }
+}
+
+bool PIDController::IsEnabled() const {
+  std::scoped_lock lock(m_thisMutex);
+  return m_enabled;
+}
+
+void PIDController::Reset() {
+  Disable();
+
+  PIDBase::Reset();
+}
+
+void PIDController::InitSendable(SendableBuilder& builder) {
+  PIDBase::InitSendable(builder);
+  builder.AddBooleanProperty("enabled", [=]() { return IsEnabled(); },
+                             [=](bool value) { SetEnabled(value); });
+}
diff --git a/wpilibc/src/main/native/cpp/PIDSource.cpp b/wpilibc/src/main/native/cpp/PIDSource.cpp
new file mode 100644
index 0000000..28291dd
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/PIDSource.cpp
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/PIDSource.h"
+
+using namespace frc;
+
+void PIDSource::SetPIDSourceType(PIDSourceType pidSource) {
+  m_pidSource = pidSource;
+}
+
+PIDSourceType PIDSource::GetPIDSourceType() const { return m_pidSource; }
diff --git a/wpilibc/src/main/native/cpp/PWM.cpp b/wpilibc/src/main/native/cpp/PWM.cpp
new file mode 100644
index 0000000..dabcd2e
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/PWM.cpp
@@ -0,0 +1,204 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/PWM.h"
+
+#include <utility>
+
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+#include <hal/PWM.h>
+#include <hal/Ports.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+PWM::PWM(int channel) {
+  if (!SensorUtil::CheckPWMChannel(channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
+                               "PWM Channel " + wpi::Twine(channel));
+    return;
+  }
+
+  int32_t status = 0;
+  m_handle = HAL_InitializePWMPort(HAL_GetPort(channel), &status);
+  if (status != 0) {
+    wpi_setHALErrorWithRange(status, 0, HAL_GetNumPWMChannels(), channel);
+    m_channel = std::numeric_limits<int>::max();
+    m_handle = HAL_kInvalidHandle;
+    return;
+  }
+
+  m_channel = channel;
+
+  HAL_SetPWMDisabled(m_handle, &status);
+  wpi_setHALError(status);
+  status = 0;
+  HAL_SetPWMEliminateDeadband(m_handle, false, &status);
+  wpi_setHALError(status);
+
+  HAL_Report(HALUsageReporting::kResourceType_PWM, channel + 1);
+  SendableRegistry::GetInstance().AddLW(this, "PWM", channel);
+
+  SetSafetyEnabled(false);
+}
+
+PWM::~PWM() {
+  int32_t status = 0;
+
+  HAL_SetPWMDisabled(m_handle, &status);
+  wpi_setHALError(status);
+
+  HAL_FreePWMPort(m_handle, &status);
+  wpi_setHALError(status);
+}
+
+void PWM::StopMotor() { SetDisabled(); }
+
+void PWM::GetDescription(wpi::raw_ostream& desc) const {
+  desc << "PWM " << GetChannel();
+}
+
+void PWM::SetRaw(uint16_t value) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_SetPWMRaw(m_handle, value, &status);
+  wpi_setHALError(status);
+}
+
+uint16_t PWM::GetRaw() const {
+  if (StatusIsFatal()) return 0;
+
+  int32_t status = 0;
+  uint16_t value = HAL_GetPWMRaw(m_handle, &status);
+  wpi_setHALError(status);
+
+  return value;
+}
+
+void PWM::SetPosition(double pos) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMPosition(m_handle, pos, &status);
+  wpi_setHALError(status);
+}
+
+double PWM::GetPosition() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double position = HAL_GetPWMPosition(m_handle, &status);
+  wpi_setHALError(status);
+  return position;
+}
+
+void PWM::SetSpeed(double speed) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMSpeed(m_handle, speed, &status);
+  wpi_setHALError(status);
+
+  Feed();
+}
+
+double PWM::GetSpeed() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double speed = HAL_GetPWMSpeed(m_handle, &status);
+  wpi_setHALError(status);
+  return speed;
+}
+
+void PWM::SetDisabled() {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  HAL_SetPWMDisabled(m_handle, &status);
+  wpi_setHALError(status);
+}
+
+void PWM::SetPeriodMultiplier(PeriodMultiplier mult) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  switch (mult) {
+    case kPeriodMultiplier_4X:
+      HAL_SetPWMPeriodScale(m_handle, 3,
+                            &status);  // Squelch 3 out of 4 outputs
+      break;
+    case kPeriodMultiplier_2X:
+      HAL_SetPWMPeriodScale(m_handle, 1,
+                            &status);  // Squelch 1 out of 2 outputs
+      break;
+    case kPeriodMultiplier_1X:
+      HAL_SetPWMPeriodScale(m_handle, 0, &status);  // Don't squelch any outputs
+      break;
+    default:
+      wpi_assert(false);
+  }
+
+  wpi_setHALError(status);
+}
+
+void PWM::SetZeroLatch() {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  HAL_LatchPWMZero(m_handle, &status);
+  wpi_setHALError(status);
+}
+
+void PWM::EnableDeadbandElimination(bool eliminateDeadband) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMEliminateDeadband(m_handle, eliminateDeadband, &status);
+  wpi_setHALError(status);
+}
+
+void PWM::SetBounds(double max, double deadbandMax, double center,
+                    double deadbandMin, double min) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMConfig(m_handle, max, deadbandMax, center, deadbandMin, min,
+                   &status);
+  wpi_setHALError(status);
+}
+
+void PWM::SetRawBounds(int max, int deadbandMax, int center, int deadbandMin,
+                       int min) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min,
+                      &status);
+  wpi_setHALError(status);
+}
+
+void PWM::GetRawBounds(int* max, int* deadbandMax, int* center,
+                       int* deadbandMin, int* min) {
+  int32_t status = 0;
+  HAL_GetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min,
+                      &status);
+  wpi_setHALError(status);
+}
+
+int PWM::GetChannel() const { return m_channel; }
+
+void PWM::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("PWM");
+  builder.SetActuator(true);
+  builder.SetSafeState([=]() { SetDisabled(); });
+  builder.AddDoubleProperty("Value", [=]() { return GetRaw(); },
+                            [=](double value) { SetRaw(value); });
+}
diff --git a/wpilibc/src/main/native/cpp/PWMSparkMax.cpp b/wpilibc/src/main/native/cpp/PWMSparkMax.cpp
new file mode 100644
index 0000000..c5375f4
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/PWMSparkMax.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/PWMSparkMax.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+PWMSparkMax::PWMSparkMax(int channel) : PWMSpeedController(channel) {
+  SetBounds(2.003, 1.55, 1.50, 1.46, 0.999);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_RevSparkMaxPWM, GetChannel() + 1);
+  SendableRegistry::GetInstance().SetName(this, "PWMSparkMax", GetChannel());
+}
diff --git a/wpilibc/src/main/native/cpp/PWMSpeedController.cpp b/wpilibc/src/main/native/cpp/PWMSpeedController.cpp
new file mode 100644
index 0000000..ea298de
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/PWMSpeedController.cpp
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/PWMSpeedController.h"
+
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+void PWMSpeedController::Set(double speed) {
+  SetSpeed(m_isInverted ? -speed : speed);
+}
+
+double PWMSpeedController::Get() const { return GetSpeed(); }
+
+void PWMSpeedController::SetInverted(bool isInverted) {
+  m_isInverted = isInverted;
+}
+
+bool PWMSpeedController::GetInverted() const { return m_isInverted; }
+
+void PWMSpeedController::Disable() { SetDisabled(); }
+
+void PWMSpeedController::StopMotor() { PWM::StopMotor(); }
+
+void PWMSpeedController::PIDWrite(double output) { Set(output); }
+
+PWMSpeedController::PWMSpeedController(int channel) : PWM(channel) {}
+
+void PWMSpeedController::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Speed Controller");
+  builder.SetActuator(true);
+  builder.SetSafeState([=]() { SetDisabled(); });
+  builder.AddDoubleProperty("Value", [=]() { return GetSpeed(); },
+                            [=](double value) { SetSpeed(value); });
+}
diff --git a/wpilibc/src/main/native/cpp/PWMTalonFX.cpp b/wpilibc/src/main/native/cpp/PWMTalonFX.cpp
new file mode 100644
index 0000000..09b7163
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/PWMTalonFX.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/PWMTalonFX.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+PWMTalonFX::PWMTalonFX(int channel) : PWMSpeedController(channel) {
+  SetBounds(2.004, 1.52, 1.50, 1.48, 0.997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_TalonFX, GetChannel() + 1);
+  SendableRegistry::GetInstance().SetName(this, "PWMTalonFX", GetChannel());
+}
diff --git a/wpilibc/src/main/native/cpp/PWMTalonSRX.cpp b/wpilibc/src/main/native/cpp/PWMTalonSRX.cpp
new file mode 100644
index 0000000..1242be9
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/PWMTalonSRX.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/PWMTalonSRX.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+PWMTalonSRX::PWMTalonSRX(int channel) : PWMSpeedController(channel) {
+  SetBounds(2.004, 1.52, 1.50, 1.48, 0.997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_PWMTalonSRX, GetChannel() + 1);
+  SendableRegistry::GetInstance().SetName(this, "PWMTalonSRX", GetChannel());
+}
diff --git a/wpilibc/src/main/native/cpp/PWMVenom.cpp b/wpilibc/src/main/native/cpp/PWMVenom.cpp
new file mode 100644
index 0000000..9fa14b7
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/PWMVenom.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/PWMVenom.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+PWMVenom::PWMVenom(int channel) : PWMSpeedController(channel) {
+  SetBounds(2.004, 1.52, 1.50, 1.48, 0.997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_FusionVenom, GetChannel() + 1);
+  SendableRegistry::GetInstance().SetName(this, "PWMVenom", GetChannel());
+}
diff --git a/wpilibc/src/main/native/cpp/PWMVictorSPX.cpp b/wpilibc/src/main/native/cpp/PWMVictorSPX.cpp
new file mode 100644
index 0000000..0d966ae
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/PWMVictorSPX.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/PWMVictorSPX.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+PWMVictorSPX::PWMVictorSPX(int channel) : PWMSpeedController(channel) {
+  SetBounds(2.004, 1.52, 1.50, 1.48, 0.997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_PWMVictorSPX, GetChannel() + 1);
+  SendableRegistry::GetInstance().SetName(this, "PWMVictorSPX", GetChannel());
+}
diff --git a/wpilibc/src/main/native/cpp/PowerDistributionPanel.cpp b/wpilibc/src/main/native/cpp/PowerDistributionPanel.cpp
new file mode 100644
index 0000000..7d7d916
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/PowerDistributionPanel.cpp
@@ -0,0 +1,148 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/PowerDistributionPanel.h"
+
+#include <hal/FRCUsageReporting.h>
+#include <hal/PDP.h>
+#include <hal/Ports.h>
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+PowerDistributionPanel::PowerDistributionPanel() : PowerDistributionPanel(0) {}
+
+/**
+ * Initialize the PDP.
+ */
+PowerDistributionPanel::PowerDistributionPanel(int module) {
+  int32_t status = 0;
+  m_handle = HAL_InitializePDP(module, &status);
+  if (status != 0) {
+    wpi_setHALErrorWithRange(status, 0, HAL_GetNumPDPModules(), module);
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_PDP, module + 1);
+  SendableRegistry::GetInstance().AddLW(this, "PowerDistributionPanel", module);
+}
+
+double PowerDistributionPanel::GetVoltage() const {
+  int32_t status = 0;
+
+  double voltage = HAL_GetPDPVoltage(m_handle, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return voltage;
+}
+
+double PowerDistributionPanel::GetTemperature() const {
+  int32_t status = 0;
+
+  double temperature = HAL_GetPDPTemperature(m_handle, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return temperature;
+}
+
+double PowerDistributionPanel::GetCurrent(int channel) const {
+  int32_t status = 0;
+
+  if (!SensorUtil::CheckPDPChannel(channel)) {
+    wpi::SmallString<32> str;
+    wpi::raw_svector_ostream buf(str);
+    buf << "PDP Channel " << channel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+  }
+
+  double current = HAL_GetPDPChannelCurrent(m_handle, channel, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return current;
+}
+
+double PowerDistributionPanel::GetTotalCurrent() const {
+  int32_t status = 0;
+
+  double current = HAL_GetPDPTotalCurrent(m_handle, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return current;
+}
+
+double PowerDistributionPanel::GetTotalPower() const {
+  int32_t status = 0;
+
+  double power = HAL_GetPDPTotalPower(m_handle, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return power;
+}
+
+double PowerDistributionPanel::GetTotalEnergy() const {
+  int32_t status = 0;
+
+  double energy = HAL_GetPDPTotalEnergy(m_handle, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return energy;
+}
+
+void PowerDistributionPanel::ResetTotalEnergy() {
+  int32_t status = 0;
+
+  HAL_ResetPDPTotalEnergy(m_handle, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+}
+
+void PowerDistributionPanel::ClearStickyFaults() {
+  int32_t status = 0;
+
+  HAL_ClearPDPStickyFaults(m_handle, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+}
+
+void PowerDistributionPanel::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("PowerDistributionPanel");
+  for (int i = 0; i < SensorUtil::kPDPChannels; ++i) {
+    builder.AddDoubleProperty("Chan" + wpi::Twine(i),
+                              [=]() { return GetCurrent(i); }, nullptr);
+  }
+  builder.AddDoubleProperty("Voltage", [=]() { return GetVoltage(); }, nullptr);
+  builder.AddDoubleProperty("TotalCurrent", [=]() { return GetTotalCurrent(); },
+                            nullptr);
+}
diff --git a/wpilibc/src/main/native/cpp/Preferences.cpp b/wpilibc/src/main/native/cpp/Preferences.cpp
new file mode 100644
index 0000000..6014775
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Preferences.cpp
@@ -0,0 +1,114 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Preferences.h"
+
+#include <algorithm>
+
+#include <hal/FRCUsageReporting.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/StringRef.h>
+
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+// The Preferences table name
+static wpi::StringRef kTableName{"Preferences"};
+
+Preferences* Preferences::GetInstance() {
+  static Preferences instance;
+  return &instance;
+}
+
+std::vector<std::string> Preferences::GetKeys() { return m_table->GetKeys(); }
+
+std::string Preferences::GetString(wpi::StringRef key,
+                                   wpi::StringRef defaultValue) {
+  return m_table->GetString(key, defaultValue);
+}
+
+int Preferences::GetInt(wpi::StringRef key, int defaultValue) {
+  return static_cast<int>(m_table->GetNumber(key, defaultValue));
+}
+
+double Preferences::GetDouble(wpi::StringRef key, double defaultValue) {
+  return m_table->GetNumber(key, defaultValue);
+}
+
+float Preferences::GetFloat(wpi::StringRef key, float defaultValue) {
+  return m_table->GetNumber(key, defaultValue);
+}
+
+bool Preferences::GetBoolean(wpi::StringRef key, bool defaultValue) {
+  return m_table->GetBoolean(key, defaultValue);
+}
+
+int64_t Preferences::GetLong(wpi::StringRef key, int64_t defaultValue) {
+  return static_cast<int64_t>(m_table->GetNumber(key, defaultValue));
+}
+
+void Preferences::PutString(wpi::StringRef key, wpi::StringRef value) {
+  auto entry = m_table->GetEntry(key);
+  entry.SetString(value);
+  entry.SetPersistent();
+}
+
+void Preferences::PutInt(wpi::StringRef key, int value) {
+  auto entry = m_table->GetEntry(key);
+  entry.SetDouble(value);
+  entry.SetPersistent();
+}
+
+void Preferences::PutDouble(wpi::StringRef key, double value) {
+  auto entry = m_table->GetEntry(key);
+  entry.SetDouble(value);
+  entry.SetPersistent();
+}
+
+void Preferences::PutFloat(wpi::StringRef key, float value) {
+  auto entry = m_table->GetEntry(key);
+  entry.SetDouble(value);
+  entry.SetPersistent();
+}
+
+void Preferences::PutBoolean(wpi::StringRef key, bool value) {
+  auto entry = m_table->GetEntry(key);
+  entry.SetBoolean(value);
+  entry.SetPersistent();
+}
+
+void Preferences::PutLong(wpi::StringRef key, int64_t value) {
+  auto entry = m_table->GetEntry(key);
+  entry.SetDouble(value);
+  entry.SetPersistent();
+}
+
+bool Preferences::ContainsKey(wpi::StringRef key) {
+  return m_table->ContainsKey(key);
+}
+
+void Preferences::Remove(wpi::StringRef key) { m_table->Delete(key); }
+
+void Preferences::RemoveAll() {
+  for (auto preference : GetKeys()) {
+    if (preference != ".type") {
+      Remove(preference);
+    }
+  }
+}
+
+Preferences::Preferences()
+    : m_table(nt::NetworkTableInstance::GetDefault().GetTable(kTableName)) {
+  m_table->GetEntry(".type").SetString("RobotPreferences");
+  m_listener = m_table->AddEntryListener(
+      [=](nt::NetworkTable* table, wpi::StringRef name,
+          nt::NetworkTableEntry entry, std::shared_ptr<nt::Value> value,
+          int flags) { entry.SetPersistent(); },
+      NT_NOTIFY_NEW | NT_NOTIFY_IMMEDIATE);
+  HAL_Report(HALUsageReporting::kResourceType_Preferences, 0);
+}
diff --git a/wpilibc/src/main/native/cpp/Relay.cpp b/wpilibc/src/main/native/cpp/Relay.cpp
new file mode 100644
index 0000000..cb95223
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Relay.cpp
@@ -0,0 +1,212 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Relay.h"
+
+#include <utility>
+
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+#include <hal/Ports.h>
+#include <hal/Relay.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+Relay::Relay(int channel, Relay::Direction direction)
+    : m_channel(channel), m_direction(direction) {
+  if (!SensorUtil::CheckRelayChannel(m_channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
+                               "Relay Channel " + wpi::Twine(m_channel));
+    return;
+  }
+
+  HAL_PortHandle portHandle = HAL_GetPort(channel);
+
+  if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+    int32_t status = 0;
+    m_forwardHandle = HAL_InitializeRelayPort(portHandle, true, &status);
+    if (status != 0) {
+      wpi_setHALErrorWithRange(status, 0, HAL_GetNumRelayChannels(), channel);
+      m_forwardHandle = HAL_kInvalidHandle;
+      m_reverseHandle = HAL_kInvalidHandle;
+      return;
+    }
+    HAL_Report(HALUsageReporting::kResourceType_Relay, m_channel + 1);
+  }
+  if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+    int32_t status = 0;
+    m_reverseHandle = HAL_InitializeRelayPort(portHandle, false, &status);
+    if (status != 0) {
+      wpi_setHALErrorWithRange(status, 0, HAL_GetNumRelayChannels(), channel);
+      m_forwardHandle = HAL_kInvalidHandle;
+      m_reverseHandle = HAL_kInvalidHandle;
+      return;
+    }
+
+    HAL_Report(HALUsageReporting::kResourceType_Relay, m_channel + 128);
+  }
+
+  int32_t status = 0;
+  if (m_forwardHandle != HAL_kInvalidHandle) {
+    HAL_SetRelay(m_forwardHandle, false, &status);
+    if (status != 0) {
+      wpi_setHALError(status);
+      m_forwardHandle = HAL_kInvalidHandle;
+      m_reverseHandle = HAL_kInvalidHandle;
+      return;
+    }
+  }
+  if (m_reverseHandle != HAL_kInvalidHandle) {
+    HAL_SetRelay(m_reverseHandle, false, &status);
+    if (status != 0) {
+      wpi_setHALError(status);
+      m_forwardHandle = HAL_kInvalidHandle;
+      m_reverseHandle = HAL_kInvalidHandle;
+      return;
+    }
+  }
+
+  SendableRegistry::GetInstance().AddLW(this, "Relay", m_channel);
+}
+
+Relay::~Relay() {
+  int32_t status = 0;
+  HAL_SetRelay(m_forwardHandle, false, &status);
+  HAL_SetRelay(m_reverseHandle, false, &status);
+  // ignore errors, as we want to make sure a free happens.
+  if (m_forwardHandle != HAL_kInvalidHandle) HAL_FreeRelayPort(m_forwardHandle);
+  if (m_reverseHandle != HAL_kInvalidHandle) HAL_FreeRelayPort(m_reverseHandle);
+}
+
+void Relay::Set(Relay::Value value) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  switch (value) {
+    case kOff:
+      if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+        HAL_SetRelay(m_forwardHandle, false, &status);
+      }
+      if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+        HAL_SetRelay(m_reverseHandle, false, &status);
+      }
+      break;
+    case kOn:
+      if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+        HAL_SetRelay(m_forwardHandle, true, &status);
+      }
+      if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+        HAL_SetRelay(m_reverseHandle, true, &status);
+      }
+      break;
+    case kForward:
+      if (m_direction == kReverseOnly) {
+        wpi_setWPIError(IncompatibleMode);
+        break;
+      }
+      if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+        HAL_SetRelay(m_forwardHandle, true, &status);
+      }
+      if (m_direction == kBothDirections) {
+        HAL_SetRelay(m_reverseHandle, false, &status);
+      }
+      break;
+    case kReverse:
+      if (m_direction == kForwardOnly) {
+        wpi_setWPIError(IncompatibleMode);
+        break;
+      }
+      if (m_direction == kBothDirections) {
+        HAL_SetRelay(m_forwardHandle, false, &status);
+      }
+      if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+        HAL_SetRelay(m_reverseHandle, true, &status);
+      }
+      break;
+  }
+
+  wpi_setHALError(status);
+}
+
+Relay::Value Relay::Get() const {
+  int32_t status;
+
+  if (m_direction == kForwardOnly) {
+    if (HAL_GetRelay(m_forwardHandle, &status)) {
+      return kOn;
+    } else {
+      return kOff;
+    }
+  } else if (m_direction == kReverseOnly) {
+    if (HAL_GetRelay(m_reverseHandle, &status)) {
+      return kOn;
+    } else {
+      return kOff;
+    }
+  } else {
+    if (HAL_GetRelay(m_forwardHandle, &status)) {
+      if (HAL_GetRelay(m_reverseHandle, &status)) {
+        return kOn;
+      } else {
+        return kForward;
+      }
+    } else {
+      if (HAL_GetRelay(m_reverseHandle, &status)) {
+        return kReverse;
+      } else {
+        return kOff;
+      }
+    }
+  }
+
+  wpi_setHALError(status);
+}
+
+int Relay::GetChannel() const { return m_channel; }
+
+void Relay::StopMotor() { Set(kOff); }
+
+void Relay::GetDescription(wpi::raw_ostream& desc) const {
+  desc << "Relay " << GetChannel();
+}
+
+void Relay::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Relay");
+  builder.SetActuator(true);
+  builder.SetSafeState([=]() { Set(kOff); });
+  builder.AddSmallStringProperty(
+      "Value",
+      [=](wpi::SmallVectorImpl<char>& buf) -> wpi::StringRef {
+        switch (Get()) {
+          case kOn:
+            return "On";
+          case kForward:
+            return "Forward";
+          case kReverse:
+            return "Reverse";
+          default:
+            return "Off";
+        }
+      },
+      [=](wpi::StringRef value) {
+        if (value == "Off")
+          Set(kOff);
+        else if (value == "Forward")
+          Set(kForward);
+        else if (value == "Reverse")
+          Set(kReverse);
+        else if (value == "On")
+          Set(kOn);
+      });
+}
diff --git a/wpilibc/src/main/native/cpp/Resource.cpp b/wpilibc/src/main/native/cpp/Resource.cpp
new file mode 100644
index 0000000..d546461
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Resource.cpp
@@ -0,0 +1,67 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Resource.h"
+
+#include "frc/ErrorBase.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+wpi::mutex Resource::m_createMutex;
+
+void Resource::CreateResourceObject(std::unique_ptr<Resource>& r,
+                                    uint32_t elements) {
+  std::scoped_lock lock(m_createMutex);
+  if (!r) {
+    r = std::make_unique<Resource>(elements);
+  }
+}
+
+Resource::Resource(uint32_t elements) {
+  m_isAllocated = std::vector<bool>(elements, false);
+}
+
+uint32_t Resource::Allocate(const std::string& resourceDesc) {
+  std::scoped_lock lock(m_allocateMutex);
+  for (uint32_t i = 0; i < m_isAllocated.size(); i++) {
+    if (!m_isAllocated[i]) {
+      m_isAllocated[i] = true;
+      return i;
+    }
+  }
+  wpi_setWPIErrorWithContext(NoAvailableResources, resourceDesc);
+  return std::numeric_limits<uint32_t>::max();
+}
+
+uint32_t Resource::Allocate(uint32_t index, const std::string& resourceDesc) {
+  std::scoped_lock lock(m_allocateMutex);
+  if (index >= m_isAllocated.size()) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, resourceDesc);
+    return std::numeric_limits<uint32_t>::max();
+  }
+  if (m_isAllocated[index]) {
+    wpi_setWPIErrorWithContext(ResourceAlreadyAllocated, resourceDesc);
+    return std::numeric_limits<uint32_t>::max();
+  }
+  m_isAllocated[index] = true;
+  return index;
+}
+
+void Resource::Free(uint32_t index) {
+  std::unique_lock lock(m_allocateMutex);
+  if (index == std::numeric_limits<uint32_t>::max()) return;
+  if (index >= m_isAllocated.size()) {
+    wpi_setWPIError(NotAllocated);
+    return;
+  }
+  if (!m_isAllocated[index]) {
+    wpi_setWPIError(NotAllocated);
+    return;
+  }
+  m_isAllocated[index] = false;
+}
diff --git a/wpilibc/src/main/native/cpp/RobotController.cpp b/wpilibc/src/main/native/cpp/RobotController.cpp
new file mode 100644
index 0000000..b1d7608
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/RobotController.cpp
@@ -0,0 +1,177 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/RobotController.h"
+
+#include <hal/CAN.h>
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+#include <hal/Power.h>
+
+#include "frc/ErrorBase.h"
+
+using namespace frc;
+
+int RobotController::GetFPGAVersion() {
+  int32_t status = 0;
+  int version = HAL_GetFPGAVersion(&status);
+  wpi_setGlobalHALError(status);
+  return version;
+}
+
+int64_t RobotController::GetFPGARevision() {
+  int32_t status = 0;
+  int64_t revision = HAL_GetFPGARevision(&status);
+  wpi_setGlobalHALError(status);
+  return revision;
+}
+
+uint64_t RobotController::GetFPGATime() {
+  int32_t status = 0;
+  uint64_t time = HAL_GetFPGATime(&status);
+  wpi_setGlobalHALError(status);
+  return time;
+}
+
+bool RobotController::GetUserButton() {
+  int32_t status = 0;
+
+  bool value = HAL_GetFPGAButton(&status);
+  wpi_setGlobalError(status);
+
+  return value;
+}
+
+bool RobotController::IsSysActive() {
+  int32_t status = 0;
+  bool retVal = HAL_GetSystemActive(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+bool RobotController::IsBrownedOut() {
+  int32_t status = 0;
+  bool retVal = HAL_GetBrownedOut(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+double RobotController::GetInputVoltage() {
+  int32_t status = 0;
+  double retVal = HAL_GetVinVoltage(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+double RobotController::GetInputCurrent() {
+  int32_t status = 0;
+  double retVal = HAL_GetVinCurrent(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+double RobotController::GetVoltage3V3() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserVoltage3V3(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+double RobotController::GetCurrent3V3() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserCurrent3V3(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+bool RobotController::GetEnabled3V3() {
+  int32_t status = 0;
+  bool retVal = HAL_GetUserActive3V3(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+int RobotController::GetFaultCount3V3() {
+  int32_t status = 0;
+  int retVal = HAL_GetUserCurrentFaults3V3(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+double RobotController::GetVoltage5V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserVoltage5V(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+double RobotController::GetCurrent5V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserCurrent5V(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+bool RobotController::GetEnabled5V() {
+  int32_t status = 0;
+  bool retVal = HAL_GetUserActive5V(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+int RobotController::GetFaultCount5V() {
+  int32_t status = 0;
+  int retVal = HAL_GetUserCurrentFaults5V(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+double RobotController::GetVoltage6V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserVoltage6V(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+double RobotController::GetCurrent6V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserCurrent6V(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+bool RobotController::GetEnabled6V() {
+  int32_t status = 0;
+  bool retVal = HAL_GetUserActive6V(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+int RobotController::GetFaultCount6V() {
+  int32_t status = 0;
+  int retVal = HAL_GetUserCurrentFaults6V(&status);
+  wpi_setGlobalHALError(status);
+  return retVal;
+}
+
+CANStatus RobotController::GetCANStatus() {
+  int32_t status = 0;
+  float percentBusUtilization = 0;
+  uint32_t busOffCount = 0;
+  uint32_t txFullCount = 0;
+  uint32_t receiveErrorCount = 0;
+  uint32_t transmitErrorCount = 0;
+  HAL_CAN_GetCANStatus(&percentBusUtilization, &busOffCount, &txFullCount,
+                       &receiveErrorCount, &transmitErrorCount, &status);
+  if (status != 0) {
+    wpi_setGlobalHALError(status);
+    return {};
+  }
+  return {percentBusUtilization, static_cast<int>(busOffCount),
+          static_cast<int>(txFullCount), static_cast<int>(receiveErrorCount),
+          static_cast<int>(transmitErrorCount)};
+}
diff --git a/wpilibc/src/main/native/cpp/RobotDrive.cpp b/wpilibc/src/main/native/cpp/RobotDrive.cpp
new file mode 100644
index 0000000..5235fa2
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/RobotDrive.cpp
@@ -0,0 +1,427 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/RobotDrive.h"
+
+#include <algorithm>
+#include <cmath>
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/GenericHID.h"
+#include "frc/Joystick.h"
+#include "frc/Talon.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+static std::shared_ptr<SpeedController> make_shared_nodelete(
+    SpeedController* ptr) {
+  return std::shared_ptr<SpeedController>(ptr, NullDeleter<SpeedController>());
+}
+
+RobotDrive::RobotDrive(int leftMotorChannel, int rightMotorChannel) {
+  InitRobotDrive();
+  m_rearLeftMotor = std::make_shared<Talon>(leftMotorChannel);
+  m_rearRightMotor = std::make_shared<Talon>(rightMotorChannel);
+  SetLeftRightMotorOutputs(0.0, 0.0);
+}
+
+RobotDrive::RobotDrive(int frontLeftMotor, int rearLeftMotor,
+                       int frontRightMotor, int rearRightMotor) {
+  InitRobotDrive();
+  m_rearLeftMotor = std::make_shared<Talon>(rearLeftMotor);
+  m_rearRightMotor = std::make_shared<Talon>(rearRightMotor);
+  m_frontLeftMotor = std::make_shared<Talon>(frontLeftMotor);
+  m_frontRightMotor = std::make_shared<Talon>(frontRightMotor);
+  SetLeftRightMotorOutputs(0.0, 0.0);
+}
+
+RobotDrive::RobotDrive(SpeedController* leftMotor,
+                       SpeedController* rightMotor) {
+  InitRobotDrive();
+  if (leftMotor == nullptr || rightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    m_rearLeftMotor = m_rearRightMotor = nullptr;
+    return;
+  }
+  m_rearLeftMotor = make_shared_nodelete(leftMotor);
+  m_rearRightMotor = make_shared_nodelete(rightMotor);
+}
+
+RobotDrive::RobotDrive(SpeedController& leftMotor,
+                       SpeedController& rightMotor) {
+  InitRobotDrive();
+  m_rearLeftMotor = make_shared_nodelete(&leftMotor);
+  m_rearRightMotor = make_shared_nodelete(&rightMotor);
+}
+
+RobotDrive::RobotDrive(std::shared_ptr<SpeedController> leftMotor,
+                       std::shared_ptr<SpeedController> rightMotor) {
+  InitRobotDrive();
+  if (leftMotor == nullptr || rightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    m_rearLeftMotor = m_rearRightMotor = nullptr;
+    return;
+  }
+  m_rearLeftMotor = leftMotor;
+  m_rearRightMotor = rightMotor;
+}
+
+RobotDrive::RobotDrive(SpeedController* frontLeftMotor,
+                       SpeedController* rearLeftMotor,
+                       SpeedController* frontRightMotor,
+                       SpeedController* rearRightMotor) {
+  InitRobotDrive();
+  if (frontLeftMotor == nullptr || rearLeftMotor == nullptr ||
+      frontRightMotor == nullptr || rearRightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  m_frontLeftMotor = make_shared_nodelete(frontLeftMotor);
+  m_rearLeftMotor = make_shared_nodelete(rearLeftMotor);
+  m_frontRightMotor = make_shared_nodelete(frontRightMotor);
+  m_rearRightMotor = make_shared_nodelete(rearRightMotor);
+}
+
+RobotDrive::RobotDrive(SpeedController& frontLeftMotor,
+                       SpeedController& rearLeftMotor,
+                       SpeedController& frontRightMotor,
+                       SpeedController& rearRightMotor) {
+  InitRobotDrive();
+  m_frontLeftMotor = make_shared_nodelete(&frontLeftMotor);
+  m_rearLeftMotor = make_shared_nodelete(&rearLeftMotor);
+  m_frontRightMotor = make_shared_nodelete(&frontRightMotor);
+  m_rearRightMotor = make_shared_nodelete(&rearRightMotor);
+}
+
+RobotDrive::RobotDrive(std::shared_ptr<SpeedController> frontLeftMotor,
+                       std::shared_ptr<SpeedController> rearLeftMotor,
+                       std::shared_ptr<SpeedController> frontRightMotor,
+                       std::shared_ptr<SpeedController> rearRightMotor) {
+  InitRobotDrive();
+  if (frontLeftMotor == nullptr || rearLeftMotor == nullptr ||
+      frontRightMotor == nullptr || rearRightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  m_frontLeftMotor = frontLeftMotor;
+  m_rearLeftMotor = rearLeftMotor;
+  m_frontRightMotor = frontRightMotor;
+  m_rearRightMotor = rearRightMotor;
+}
+
+void RobotDrive::Drive(double outputMagnitude, double curve) {
+  double leftOutput, rightOutput;
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
+               HALUsageReporting::kRobotDrive_ArcadeRatioCurve, GetNumMotors());
+    reported = true;
+  }
+
+  if (curve < 0) {
+    double value = std::log(-curve);
+    double ratio = (value - m_sensitivity) / (value + m_sensitivity);
+    if (ratio == 0) ratio = 0.0000000001;
+    leftOutput = outputMagnitude / ratio;
+    rightOutput = outputMagnitude;
+  } else if (curve > 0) {
+    double value = std::log(curve);
+    double ratio = (value - m_sensitivity) / (value + m_sensitivity);
+    if (ratio == 0) ratio = 0.0000000001;
+    leftOutput = outputMagnitude;
+    rightOutput = outputMagnitude / ratio;
+  } else {
+    leftOutput = outputMagnitude;
+    rightOutput = outputMagnitude;
+  }
+  SetLeftRightMotorOutputs(leftOutput, rightOutput);
+}
+
+void RobotDrive::TankDrive(GenericHID* leftStick, GenericHID* rightStick,
+                           bool squaredInputs) {
+  if (leftStick == nullptr || rightStick == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  TankDrive(leftStick->GetY(), rightStick->GetY(), squaredInputs);
+}
+
+void RobotDrive::TankDrive(GenericHID& leftStick, GenericHID& rightStick,
+                           bool squaredInputs) {
+  TankDrive(leftStick.GetY(), rightStick.GetY(), squaredInputs);
+}
+
+void RobotDrive::TankDrive(GenericHID* leftStick, int leftAxis,
+                           GenericHID* rightStick, int rightAxis,
+                           bool squaredInputs) {
+  if (leftStick == nullptr || rightStick == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  TankDrive(leftStick->GetRawAxis(leftAxis), rightStick->GetRawAxis(rightAxis),
+            squaredInputs);
+}
+
+void RobotDrive::TankDrive(GenericHID& leftStick, int leftAxis,
+                           GenericHID& rightStick, int rightAxis,
+                           bool squaredInputs) {
+  TankDrive(leftStick.GetRawAxis(leftAxis), rightStick.GetRawAxis(rightAxis),
+            squaredInputs);
+}
+
+void RobotDrive::TankDrive(double leftValue, double rightValue,
+                           bool squaredInputs) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
+               HALUsageReporting::kRobotDrive_Tank, GetNumMotors());
+    reported = true;
+  }
+
+  leftValue = Limit(leftValue);
+  rightValue = Limit(rightValue);
+
+  // square the inputs (while preserving the sign) to increase fine control
+  // while permitting full power
+  if (squaredInputs) {
+    leftValue = std::copysign(leftValue * leftValue, leftValue);
+    rightValue = std::copysign(rightValue * rightValue, rightValue);
+  }
+
+  SetLeftRightMotorOutputs(leftValue, rightValue);
+}
+
+void RobotDrive::ArcadeDrive(GenericHID* stick, bool squaredInputs) {
+  // simply call the full-featured ArcadeDrive with the appropriate values
+  ArcadeDrive(stick->GetY(), stick->GetX(), squaredInputs);
+}
+
+void RobotDrive::ArcadeDrive(GenericHID& stick, bool squaredInputs) {
+  // simply call the full-featured ArcadeDrive with the appropriate values
+  ArcadeDrive(stick.GetY(), stick.GetX(), squaredInputs);
+}
+
+void RobotDrive::ArcadeDrive(GenericHID* moveStick, int moveAxis,
+                             GenericHID* rotateStick, int rotateAxis,
+                             bool squaredInputs) {
+  double moveValue = moveStick->GetRawAxis(moveAxis);
+  double rotateValue = rotateStick->GetRawAxis(rotateAxis);
+
+  ArcadeDrive(moveValue, rotateValue, squaredInputs);
+}
+
+void RobotDrive::ArcadeDrive(GenericHID& moveStick, int moveAxis,
+                             GenericHID& rotateStick, int rotateAxis,
+                             bool squaredInputs) {
+  double moveValue = moveStick.GetRawAxis(moveAxis);
+  double rotateValue = rotateStick.GetRawAxis(rotateAxis);
+
+  ArcadeDrive(moveValue, rotateValue, squaredInputs);
+}
+
+void RobotDrive::ArcadeDrive(double moveValue, double rotateValue,
+                             bool squaredInputs) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
+               HALUsageReporting::kRobotDrive_ArcadeStandard, GetNumMotors());
+    reported = true;
+  }
+
+  // local variables to hold the computed PWM values for the motors
+  double leftMotorOutput;
+  double rightMotorOutput;
+
+  moveValue = Limit(moveValue);
+  rotateValue = Limit(rotateValue);
+
+  // square the inputs (while preserving the sign) to increase fine control
+  // while permitting full power
+  if (squaredInputs) {
+    moveValue = std::copysign(moveValue * moveValue, moveValue);
+    rotateValue = std::copysign(rotateValue * rotateValue, rotateValue);
+  }
+
+  if (moveValue > 0.0) {
+    if (rotateValue > 0.0) {
+      leftMotorOutput = moveValue - rotateValue;
+      rightMotorOutput = std::max(moveValue, rotateValue);
+    } else {
+      leftMotorOutput = std::max(moveValue, -rotateValue);
+      rightMotorOutput = moveValue + rotateValue;
+    }
+  } else {
+    if (rotateValue > 0.0) {
+      leftMotorOutput = -std::max(-moveValue, rotateValue);
+      rightMotorOutput = moveValue + rotateValue;
+    } else {
+      leftMotorOutput = moveValue - rotateValue;
+      rightMotorOutput = -std::max(-moveValue, -rotateValue);
+    }
+  }
+  SetLeftRightMotorOutputs(leftMotorOutput, rightMotorOutput);
+}
+
+void RobotDrive::MecanumDrive_Cartesian(double x, double y, double rotation,
+                                        double gyroAngle) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
+               HALUsageReporting::kRobotDrive_MecanumCartesian, GetNumMotors());
+    reported = true;
+  }
+
+  double xIn = x;
+  double yIn = y;
+  // Negate y for the joystick.
+  yIn = -yIn;
+  // Compenstate for gyro angle.
+  RotateVector(xIn, yIn, gyroAngle);
+
+  double wheelSpeeds[kMaxNumberOfMotors];
+  wheelSpeeds[kFrontLeftMotor] = xIn + yIn + rotation;
+  wheelSpeeds[kFrontRightMotor] = -xIn + yIn - rotation;
+  wheelSpeeds[kRearLeftMotor] = -xIn + yIn + rotation;
+  wheelSpeeds[kRearRightMotor] = xIn + yIn - rotation;
+
+  Normalize(wheelSpeeds);
+
+  m_frontLeftMotor->Set(wheelSpeeds[kFrontLeftMotor] * m_maxOutput);
+  m_frontRightMotor->Set(wheelSpeeds[kFrontRightMotor] * m_maxOutput);
+  m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_maxOutput);
+  m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_maxOutput);
+
+  Feed();
+}
+
+void RobotDrive::MecanumDrive_Polar(double magnitude, double direction,
+                                    double rotation) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
+               HALUsageReporting::kRobotDrive_MecanumPolar, GetNumMotors());
+    reported = true;
+  }
+
+  // Normalized for full power along the Cartesian axes.
+  magnitude = Limit(magnitude) * std::sqrt(2.0);
+  // The rollers are at 45 degree angles.
+  double dirInRad = (direction + 45.0) * 3.14159 / 180.0;
+  double cosD = std::cos(dirInRad);
+  double sinD = std::sin(dirInRad);
+
+  double wheelSpeeds[kMaxNumberOfMotors];
+  wheelSpeeds[kFrontLeftMotor] = sinD * magnitude + rotation;
+  wheelSpeeds[kFrontRightMotor] = cosD * magnitude - rotation;
+  wheelSpeeds[kRearLeftMotor] = cosD * magnitude + rotation;
+  wheelSpeeds[kRearRightMotor] = sinD * magnitude - rotation;
+
+  Normalize(wheelSpeeds);
+
+  m_frontLeftMotor->Set(wheelSpeeds[kFrontLeftMotor] * m_maxOutput);
+  m_frontRightMotor->Set(wheelSpeeds[kFrontRightMotor] * m_maxOutput);
+  m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_maxOutput);
+  m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_maxOutput);
+
+  Feed();
+}
+
+void RobotDrive::HolonomicDrive(double magnitude, double direction,
+                                double rotation) {
+  MecanumDrive_Polar(magnitude, direction, rotation);
+}
+
+void RobotDrive::SetLeftRightMotorOutputs(double leftOutput,
+                                          double rightOutput) {
+  wpi_assert(m_rearLeftMotor != nullptr && m_rearRightMotor != nullptr);
+
+  if (m_frontLeftMotor != nullptr)
+    m_frontLeftMotor->Set(Limit(leftOutput) * m_maxOutput);
+  m_rearLeftMotor->Set(Limit(leftOutput) * m_maxOutput);
+
+  if (m_frontRightMotor != nullptr)
+    m_frontRightMotor->Set(-Limit(rightOutput) * m_maxOutput);
+  m_rearRightMotor->Set(-Limit(rightOutput) * m_maxOutput);
+
+  Feed();
+}
+
+void RobotDrive::SetInvertedMotor(MotorType motor, bool isInverted) {
+  if (motor < 0 || motor > 3) {
+    wpi_setWPIError(InvalidMotorIndex);
+    return;
+  }
+  switch (motor) {
+    case kFrontLeftMotor:
+      m_frontLeftMotor->SetInverted(isInverted);
+      break;
+    case kFrontRightMotor:
+      m_frontRightMotor->SetInverted(isInverted);
+      break;
+    case kRearLeftMotor:
+      m_rearLeftMotor->SetInverted(isInverted);
+      break;
+    case kRearRightMotor:
+      m_rearRightMotor->SetInverted(isInverted);
+      break;
+  }
+}
+
+void RobotDrive::SetSensitivity(double sensitivity) {
+  m_sensitivity = sensitivity;
+}
+
+void RobotDrive::SetMaxOutput(double maxOutput) { m_maxOutput = maxOutput; }
+
+void RobotDrive::GetDescription(wpi::raw_ostream& desc) const {
+  desc << "RobotDrive";
+}
+
+void RobotDrive::StopMotor() {
+  if (m_frontLeftMotor != nullptr) m_frontLeftMotor->StopMotor();
+  if (m_frontRightMotor != nullptr) m_frontRightMotor->StopMotor();
+  if (m_rearLeftMotor != nullptr) m_rearLeftMotor->StopMotor();
+  if (m_rearRightMotor != nullptr) m_rearRightMotor->StopMotor();
+  Feed();
+}
+
+void RobotDrive::InitRobotDrive() { SetSafetyEnabled(true); }
+
+double RobotDrive::Limit(double number) {
+  if (number > 1.0) {
+    return 1.0;
+  }
+  if (number < -1.0) {
+    return -1.0;
+  }
+  return number;
+}
+
+void RobotDrive::Normalize(double* wheelSpeeds) {
+  double maxMagnitude = std::fabs(wheelSpeeds[0]);
+  for (int i = 1; i < kMaxNumberOfMotors; i++) {
+    double temp = std::fabs(wheelSpeeds[i]);
+    if (maxMagnitude < temp) maxMagnitude = temp;
+  }
+  if (maxMagnitude > 1.0) {
+    for (int i = 0; i < kMaxNumberOfMotors; i++) {
+      wheelSpeeds[i] = wheelSpeeds[i] / maxMagnitude;
+    }
+  }
+}
+
+void RobotDrive::RotateVector(double& x, double& y, double angle) {
+  double cosA = std::cos(angle * (3.14159 / 180.0));
+  double sinA = std::sin(angle * (3.14159 / 180.0));
+  double xOut = x * cosA - y * sinA;
+  double yOut = x * sinA + y * cosA;
+  x = xOut;
+  y = yOut;
+}
diff --git a/wpilibc/src/main/native/cpp/RobotState.cpp b/wpilibc/src/main/native/cpp/RobotState.cpp
new file mode 100644
index 0000000..530cee3
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/RobotState.cpp
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/RobotState.h"
+
+#include "frc/DriverStation.h"
+
+using namespace frc;
+
+bool RobotState::IsDisabled() {
+  return DriverStation::GetInstance().IsDisabled();
+}
+
+bool RobotState::IsEnabled() {
+  return DriverStation::GetInstance().IsEnabled();
+}
+
+bool RobotState::IsEStopped() {
+  return DriverStation::GetInstance().IsEStopped();
+}
+
+bool RobotState::IsOperatorControl() {
+  return DriverStation::GetInstance().IsOperatorControl();
+}
+
+bool RobotState::IsAutonomous() {
+  return DriverStation::GetInstance().IsAutonomous();
+}
+
+bool RobotState::IsTest() { return DriverStation::GetInstance().IsTest(); }
diff --git a/wpilibc/src/main/native/cpp/SD540.cpp b/wpilibc/src/main/native/cpp/SD540.cpp
new file mode 100644
index 0000000..9611f66
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/SD540.cpp
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/SD540.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+SD540::SD540(int channel) : PWMSpeedController(channel) {
+  SetBounds(2.05, 1.55, 1.50, 1.44, 0.94);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_MindsensorsSD540,
+             GetChannel() + 1);
+  SendableRegistry::GetInstance().SetName(this, "SD540", GetChannel());
+}
diff --git a/wpilibc/src/main/native/cpp/SPI.cpp b/wpilibc/src/main/native/cpp/SPI.cpp
new file mode 100644
index 0000000..d51fa3b
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/SPI.cpp
@@ -0,0 +1,444 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/SPI.h"
+
+#include <cstring>
+#include <utility>
+
+#include <hal/FRCUsageReporting.h>
+#include <hal/SPI.h>
+#include <wpi/SmallVector.h>
+#include <wpi/mutex.h>
+
+#include "frc/DigitalSource.h"
+#include "frc/Notifier.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+static constexpr int kAccumulateDepth = 2048;
+
+class SPI::Accumulator {
+ public:
+  Accumulator(HAL_SPIPort port, int xferSize, int validMask, int validValue,
+              int dataShift, int dataSize, bool isSigned, bool bigEndian)
+      : m_notifier([=]() {
+          std::scoped_lock lock(m_mutex);
+          Update();
+        }),
+        m_buf(new uint32_t[(xferSize + 1) * kAccumulateDepth]),
+        m_validMask(validMask),
+        m_validValue(validValue),
+        m_dataMax(1 << dataSize),
+        m_dataMsbMask(1 << (dataSize - 1)),
+        m_dataShift(dataShift),
+        m_xferSize(xferSize + 1),  // +1 for timestamp
+        m_isSigned(isSigned),
+        m_bigEndian(bigEndian),
+        m_port(port) {}
+  ~Accumulator() { delete[] m_buf; }
+
+  void Update();
+
+  Notifier m_notifier;
+  uint32_t* m_buf;
+  wpi::mutex m_mutex;
+
+  int64_t m_value = 0;
+  uint32_t m_count = 0;
+  int32_t m_lastValue = 0;
+  uint32_t m_lastTimestamp = 0;
+  double m_integratedValue = 0;
+
+  int32_t m_center = 0;
+  int32_t m_deadband = 0;
+  double m_integratedCenter = 0;
+
+  int32_t m_validMask;
+  int32_t m_validValue;
+  int32_t m_dataMax;      // one more than max data value
+  int32_t m_dataMsbMask;  // data field MSB mask (for signed)
+  uint8_t m_dataShift;    // data field shift right amount, in bits
+  int32_t m_xferSize;     // SPI transfer size, in bytes
+  bool m_isSigned;        // is data field signed?
+  bool m_bigEndian;       // is response big endian?
+  HAL_SPIPort m_port;
+};
+
+void SPI::Accumulator::Update() {
+  bool done;
+  do {
+    done = true;
+    int32_t status = 0;
+
+    // get amount of data available
+    int32_t numToRead =
+        HAL_ReadSPIAutoReceivedData(m_port, m_buf, 0, 0, &status);
+    if (status != 0) return;  // error reading
+
+    // only get whole responses; +1 is for timestamp
+    numToRead -= numToRead % m_xferSize;
+    if (numToRead > m_xferSize * kAccumulateDepth) {
+      numToRead = m_xferSize * kAccumulateDepth;
+      done = false;
+    }
+    if (numToRead == 0) return;  // no samples
+
+    // read buffered data
+    HAL_ReadSPIAutoReceivedData(m_port, m_buf, numToRead, 0, &status);
+    if (status != 0) return;  // error reading
+
+    // loop over all responses
+    for (int32_t off = 0; off < numToRead; off += m_xferSize) {
+      // get timestamp from first word
+      uint32_t timestamp = m_buf[off];
+
+      // convert from bytes
+      uint32_t resp = 0;
+      if (m_bigEndian) {
+        for (int32_t i = 1; i < m_xferSize; ++i) {
+          resp <<= 8;
+          resp |= m_buf[off + i] & 0xff;
+        }
+      } else {
+        for (int32_t i = m_xferSize - 1; i >= 1; --i) {
+          resp <<= 8;
+          resp |= m_buf[off + i] & 0xff;
+        }
+      }
+
+      // process response
+      if ((resp & m_validMask) == static_cast<uint32_t>(m_validValue)) {
+        // valid sensor data; extract data field
+        int32_t data = static_cast<int32_t>(resp >> m_dataShift);
+        data &= m_dataMax - 1;
+        // 2s complement conversion if signed MSB is set
+        if (m_isSigned && (data & m_dataMsbMask) != 0) data -= m_dataMax;
+        // center offset
+        int32_t dataNoCenter = data;
+        data -= m_center;
+        // only accumulate if outside deadband
+        if (data < -m_deadband || data > m_deadband) {
+          m_value += data;
+          if (m_count != 0) {
+            // timestamps use the 1us FPGA clock; also handle rollover
+            if (timestamp >= m_lastTimestamp)
+              m_integratedValue +=
+                  dataNoCenter *
+                      static_cast<int32_t>(timestamp - m_lastTimestamp) * 1e-6 -
+                  m_integratedCenter;
+            else
+              m_integratedValue +=
+                  dataNoCenter *
+                      static_cast<int32_t>((1ULL << 32) - m_lastTimestamp +
+                                           timestamp) *
+                      1e-6 -
+                  m_integratedCenter;
+          }
+        }
+        ++m_count;
+        m_lastValue = data;
+      } else {
+        // no data from the sensor; just clear the last value
+        m_lastValue = 0;
+      }
+      m_lastTimestamp = timestamp;
+    }
+  } while (!done);
+}
+
+SPI::SPI(Port port) : m_port(static_cast<HAL_SPIPort>(port)) {
+  int32_t status = 0;
+  HAL_InitializeSPI(m_port, &status);
+  wpi_setHALError(status);
+
+  HAL_Report(HALUsageReporting::kResourceType_SPI,
+             static_cast<uint8_t>(port) + 1);
+}
+
+SPI::~SPI() { HAL_CloseSPI(m_port); }
+
+void SPI::SetClockRate(int hz) { HAL_SetSPISpeed(m_port, hz); }
+
+void SPI::SetMSBFirst() {
+  m_msbFirst = true;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetLSBFirst() {
+  m_msbFirst = false;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetSampleDataOnLeadingEdge() {
+  m_sampleOnTrailing = false;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetSampleDataOnTrailingEdge() {
+  m_sampleOnTrailing = true;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetSampleDataOnFalling() {
+  m_sampleOnTrailing = true;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetSampleDataOnRising() {
+  m_sampleOnTrailing = false;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetClockActiveLow() {
+  m_clockIdleHigh = true;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetClockActiveHigh() {
+  m_clockIdleHigh = false;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetChipSelectActiveHigh() {
+  int32_t status = 0;
+  HAL_SetSPIChipSelectActiveHigh(m_port, &status);
+  wpi_setHALError(status);
+}
+
+void SPI::SetChipSelectActiveLow() {
+  int32_t status = 0;
+  HAL_SetSPIChipSelectActiveLow(m_port, &status);
+  wpi_setHALError(status);
+}
+
+int SPI::Write(uint8_t* data, int size) {
+  int retVal = 0;
+  retVal = HAL_WriteSPI(m_port, data, size);
+  return retVal;
+}
+
+int SPI::Read(bool initiate, uint8_t* dataReceived, int size) {
+  int retVal = 0;
+  if (initiate) {
+    wpi::SmallVector<uint8_t, 32> dataToSend;
+    dataToSend.resize(size);
+    retVal = HAL_TransactionSPI(m_port, dataToSend.data(), dataReceived, size);
+  } else {
+    retVal = HAL_ReadSPI(m_port, dataReceived, size);
+  }
+  return retVal;
+}
+
+int SPI::Transaction(uint8_t* dataToSend, uint8_t* dataReceived, int size) {
+  int retVal = 0;
+  retVal = HAL_TransactionSPI(m_port, dataToSend, dataReceived, size);
+  return retVal;
+}
+
+void SPI::InitAuto(int bufferSize) {
+  int32_t status = 0;
+  HAL_InitSPIAuto(m_port, bufferSize, &status);
+  wpi_setHALError(status);
+}
+
+void SPI::FreeAuto() {
+  int32_t status = 0;
+  HAL_FreeSPIAuto(m_port, &status);
+  wpi_setHALError(status);
+}
+
+void SPI::SetAutoTransmitData(wpi::ArrayRef<uint8_t> dataToSend, int zeroSize) {
+  int32_t status = 0;
+  HAL_SetSPIAutoTransmitData(m_port, dataToSend.data(), dataToSend.size(),
+                             zeroSize, &status);
+  wpi_setHALError(status);
+}
+
+void SPI::StartAutoRate(units::second_t period) {
+  int32_t status = 0;
+  HAL_StartSPIAutoRate(m_port, period.to<double>(), &status);
+  wpi_setHALError(status);
+}
+
+void SPI::StartAutoRate(double period) {
+  StartAutoRate(units::second_t(period));
+}
+
+void SPI::StartAutoTrigger(DigitalSource& source, bool rising, bool falling) {
+  int32_t status = 0;
+  HAL_StartSPIAutoTrigger(
+      m_port, source.GetPortHandleForRouting(),
+      (HAL_AnalogTriggerType)source.GetAnalogTriggerTypeForRouting(), rising,
+      falling, &status);
+  wpi_setHALError(status);
+}
+
+void SPI::StopAuto() {
+  int32_t status = 0;
+  HAL_StopSPIAuto(m_port, &status);
+  wpi_setHALError(status);
+}
+
+void SPI::ForceAutoRead() {
+  int32_t status = 0;
+  HAL_ForceSPIAutoRead(m_port, &status);
+  wpi_setHALError(status);
+}
+
+int SPI::ReadAutoReceivedData(uint32_t* buffer, int numToRead,
+                              units::second_t timeout) {
+  int32_t status = 0;
+  int32_t val = HAL_ReadSPIAutoReceivedData(m_port, buffer, numToRead,
+                                            timeout.to<double>(), &status);
+  wpi_setHALError(status);
+  return val;
+}
+
+int SPI::ReadAutoReceivedData(uint32_t* buffer, int numToRead, double timeout) {
+  return ReadAutoReceivedData(buffer, numToRead, units::second_t(timeout));
+}
+
+int SPI::GetAutoDroppedCount() {
+  int32_t status = 0;
+  int32_t val = HAL_GetSPIAutoDroppedCount(m_port, &status);
+  wpi_setHALError(status);
+  return val;
+}
+
+void SPI::ConfigureAutoStall(HAL_SPIPort port, int csToSclkTicks,
+                             int stallTicks, int pow2BytesPerRead) {
+  int32_t status = 0;
+  HAL_ConfigureSPIAutoStall(m_port, csToSclkTicks, stallTicks, pow2BytesPerRead,
+                            &status);
+  wpi_setHALError(status);
+}
+
+void SPI::InitAccumulator(units::second_t period, int cmd, int xferSize,
+                          int validMask, int validValue, int dataShift,
+                          int dataSize, bool isSigned, bool bigEndian) {
+  InitAuto(xferSize * kAccumulateDepth);
+  uint8_t cmdBytes[4] = {0, 0, 0, 0};
+  if (bigEndian) {
+    for (int32_t i = xferSize - 1; i >= 0; --i) {
+      cmdBytes[i] = cmd & 0xff;
+      cmd >>= 8;
+    }
+  } else {
+    cmdBytes[0] = cmd & 0xff;
+    cmd >>= 8;
+    cmdBytes[1] = cmd & 0xff;
+    cmd >>= 8;
+    cmdBytes[2] = cmd & 0xff;
+    cmd >>= 8;
+    cmdBytes[3] = cmd & 0xff;
+  }
+  SetAutoTransmitData(cmdBytes, xferSize - 4);
+  StartAutoRate(period);
+
+  m_accum.reset(new Accumulator(m_port, xferSize, validMask, validValue,
+                                dataShift, dataSize, isSigned, bigEndian));
+  m_accum->m_notifier.StartPeriodic(period * kAccumulateDepth / 2);
+}
+
+void SPI::InitAccumulator(double period, int cmd, int xferSize, int validMask,
+                          int validValue, int dataShift, int dataSize,
+                          bool isSigned, bool bigEndian) {
+  InitAccumulator(units::second_t(period), cmd, xferSize, validMask, validValue,
+                  dataShift, dataSize, isSigned, bigEndian);
+}
+
+void SPI::FreeAccumulator() {
+  m_accum.reset(nullptr);
+  FreeAuto();
+}
+
+void SPI::ResetAccumulator() {
+  if (!m_accum) return;
+  std::scoped_lock lock(m_accum->m_mutex);
+  m_accum->m_value = 0;
+  m_accum->m_count = 0;
+  m_accum->m_lastValue = 0;
+  m_accum->m_lastTimestamp = 0;
+  m_accum->m_integratedValue = 0;
+}
+
+void SPI::SetAccumulatorCenter(int center) {
+  if (!m_accum) return;
+  std::scoped_lock lock(m_accum->m_mutex);
+  m_accum->m_center = center;
+}
+
+void SPI::SetAccumulatorDeadband(int deadband) {
+  if (!m_accum) return;
+  std::scoped_lock lock(m_accum->m_mutex);
+  m_accum->m_deadband = deadband;
+}
+
+int SPI::GetAccumulatorLastValue() const {
+  if (!m_accum) return 0;
+  std::scoped_lock lock(m_accum->m_mutex);
+  m_accum->Update();
+  return m_accum->m_lastValue;
+}
+
+int64_t SPI::GetAccumulatorValue() const {
+  if (!m_accum) return 0;
+  std::scoped_lock lock(m_accum->m_mutex);
+  m_accum->Update();
+  return m_accum->m_value;
+}
+
+int64_t SPI::GetAccumulatorCount() const {
+  if (!m_accum) return 0;
+  std::scoped_lock lock(m_accum->m_mutex);
+  m_accum->Update();
+  return m_accum->m_count;
+}
+
+double SPI::GetAccumulatorAverage() const {
+  if (!m_accum) return 0;
+  std::scoped_lock lock(m_accum->m_mutex);
+  m_accum->Update();
+  if (m_accum->m_count == 0) return 0.0;
+  return static_cast<double>(m_accum->m_value) / m_accum->m_count;
+}
+
+void SPI::GetAccumulatorOutput(int64_t& value, int64_t& count) const {
+  if (!m_accum) {
+    value = 0;
+    count = 0;
+    return;
+  }
+  std::scoped_lock lock(m_accum->m_mutex);
+  m_accum->Update();
+  value = m_accum->m_value;
+  count = m_accum->m_count;
+}
+
+void SPI::SetAccumulatorIntegratedCenter(double center) {
+  if (!m_accum) return;
+  std::scoped_lock lock(m_accum->m_mutex);
+  m_accum->m_integratedCenter = center;
+}
+
+double SPI::GetAccumulatorIntegratedValue() const {
+  if (!m_accum) return 0;
+  std::scoped_lock lock(m_accum->m_mutex);
+  m_accum->Update();
+  return m_accum->m_integratedValue;
+}
+
+double SPI::GetAccumulatorIntegratedAverage() const {
+  if (!m_accum) return 0;
+  std::scoped_lock lock(m_accum->m_mutex);
+  m_accum->Update();
+  if (m_accum->m_count <= 1) return 0.0;
+  // count-1 due to not integrating the first value received
+  return m_accum->m_integratedValue / (m_accum->m_count - 1);
+}
diff --git a/wpilibc/src/main/native/cpp/SensorUtil.cpp b/wpilibc/src/main/native/cpp/SensorUtil.cpp
new file mode 100644
index 0000000..8c02f1b
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/SensorUtil.cpp
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/SensorUtil.h"
+
+#include <hal/AnalogInput.h>
+#include <hal/AnalogOutput.h>
+#include <hal/DIO.h>
+#include <hal/FRCUsageReporting.h>
+#include <hal/PDP.h>
+#include <hal/PWM.h>
+#include <hal/Ports.h>
+#include <hal/Relay.h>
+#include <hal/Solenoid.h>
+
+using namespace frc;
+
+const int SensorUtil::kDigitalChannels = HAL_GetNumDigitalChannels();
+const int SensorUtil::kAnalogInputs = HAL_GetNumAnalogInputs();
+const int SensorUtil::kSolenoidChannels = HAL_GetNumSolenoidChannels();
+const int SensorUtil::kSolenoidModules = HAL_GetNumPCMModules();
+const int SensorUtil::kPwmChannels = HAL_GetNumPWMChannels();
+const int SensorUtil::kRelayChannels = HAL_GetNumRelayHeaders();
+const int SensorUtil::kPDPChannels = HAL_GetNumPDPChannels();
+
+int SensorUtil::GetDefaultSolenoidModule() { return 0; }
+
+bool SensorUtil::CheckSolenoidModule(int moduleNumber) {
+  return HAL_CheckSolenoidModule(moduleNumber);
+}
+
+bool SensorUtil::CheckDigitalChannel(int channel) {
+  return HAL_CheckDIOChannel(channel);
+}
+
+bool SensorUtil::CheckRelayChannel(int channel) {
+  return HAL_CheckRelayChannel(channel);
+}
+
+bool SensorUtil::CheckPWMChannel(int channel) {
+  return HAL_CheckPWMChannel(channel);
+}
+
+bool SensorUtil::CheckAnalogInputChannel(int channel) {
+  return HAL_CheckAnalogInputChannel(channel);
+}
+
+bool SensorUtil::CheckAnalogOutputChannel(int channel) {
+  return HAL_CheckAnalogOutputChannel(channel);
+}
+
+bool SensorUtil::CheckSolenoidChannel(int channel) {
+  return HAL_CheckSolenoidChannel(channel);
+}
+
+bool SensorUtil::CheckPDPChannel(int channel) {
+  return HAL_CheckPDPChannel(channel);
+}
+
+bool SensorUtil::CheckPDPModule(int module) {
+  return HAL_CheckPDPModule(module);
+}
diff --git a/wpilibc/src/main/native/cpp/SerialPort.cpp b/wpilibc/src/main/native/cpp/SerialPort.cpp
new file mode 100644
index 0000000..e092fc2
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/SerialPort.cpp
@@ -0,0 +1,166 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/SerialPort.h"
+
+#include <utility>
+
+#include <hal/FRCUsageReporting.h>
+#include <hal/SerialPort.h>
+
+using namespace frc;
+
+SerialPort::SerialPort(int baudRate, Port port, int dataBits,
+                       SerialPort::Parity parity,
+                       SerialPort::StopBits stopBits) {
+  int32_t status = 0;
+
+  m_portHandle =
+      HAL_InitializeSerialPort(static_cast<HAL_SerialPort>(port), &status);
+  wpi_setHALError(status);
+  // Don't continue if initialization failed
+  if (status < 0) return;
+  HAL_SetSerialBaudRate(m_portHandle, baudRate, &status);
+  wpi_setHALError(status);
+  HAL_SetSerialDataBits(m_portHandle, dataBits, &status);
+  wpi_setHALError(status);
+  HAL_SetSerialParity(m_portHandle, parity, &status);
+  wpi_setHALError(status);
+  HAL_SetSerialStopBits(m_portHandle, stopBits, &status);
+  wpi_setHALError(status);
+
+  // Set the default timeout to 5 seconds.
+  SetTimeout(5.0);
+
+  // Don't wait until the buffer is full to transmit.
+  SetWriteBufferMode(kFlushOnAccess);
+
+  DisableTermination();
+
+  HAL_Report(HALUsageReporting::kResourceType_SerialPort,
+             static_cast<uint8_t>(port) + 1);
+}
+
+SerialPort::SerialPort(int baudRate, const wpi::Twine& portName, Port port,
+                       int dataBits, SerialPort::Parity parity,
+                       SerialPort::StopBits stopBits) {
+  int32_t status = 0;
+
+  wpi::SmallVector<char, 64> buf;
+  const char* portNameC = portName.toNullTerminatedStringRef(buf).data();
+
+  m_portHandle = HAL_InitializeSerialPortDirect(
+      static_cast<HAL_SerialPort>(port), portNameC, &status);
+  wpi_setHALError(status);
+  // Don't continue if initialization failed
+  if (status < 0) return;
+  HAL_SetSerialBaudRate(m_portHandle, baudRate, &status);
+  wpi_setHALError(status);
+  HAL_SetSerialDataBits(m_portHandle, dataBits, &status);
+  wpi_setHALError(status);
+  HAL_SetSerialParity(m_portHandle, parity, &status);
+  wpi_setHALError(status);
+  HAL_SetSerialStopBits(m_portHandle, stopBits, &status);
+  wpi_setHALError(status);
+
+  // Set the default timeout to 5 seconds.
+  SetTimeout(5.0);
+
+  // Don't wait until the buffer is full to transmit.
+  SetWriteBufferMode(kFlushOnAccess);
+
+  DisableTermination();
+
+  HAL_Report(HALUsageReporting::kResourceType_SerialPort,
+             static_cast<uint8_t>(port) + 1);
+}
+
+SerialPort::~SerialPort() {
+  int32_t status = 0;
+  HAL_CloseSerial(m_portHandle, &status);
+  wpi_setHALError(status);
+}
+
+void SerialPort::SetFlowControl(SerialPort::FlowControl flowControl) {
+  int32_t status = 0;
+  HAL_SetSerialFlowControl(m_portHandle, flowControl, &status);
+  wpi_setHALError(status);
+}
+
+void SerialPort::EnableTermination(char terminator) {
+  int32_t status = 0;
+  HAL_EnableSerialTermination(m_portHandle, terminator, &status);
+  wpi_setHALError(status);
+}
+
+void SerialPort::DisableTermination() {
+  int32_t status = 0;
+  HAL_DisableSerialTermination(m_portHandle, &status);
+  wpi_setHALError(status);
+}
+
+int SerialPort::GetBytesReceived() {
+  int32_t status = 0;
+  int retVal = HAL_GetSerialBytesReceived(m_portHandle, &status);
+  wpi_setHALError(status);
+  return retVal;
+}
+
+int SerialPort::Read(char* buffer, int count) {
+  int32_t status = 0;
+  int retVal = HAL_ReadSerial(m_portHandle, buffer, count, &status);
+  wpi_setHALError(status);
+  return retVal;
+}
+
+int SerialPort::Write(const char* buffer, int count) {
+  return Write(wpi::StringRef(buffer, static_cast<size_t>(count)));
+}
+
+int SerialPort::Write(wpi::StringRef buffer) {
+  int32_t status = 0;
+  int retVal =
+      HAL_WriteSerial(m_portHandle, buffer.data(), buffer.size(), &status);
+  wpi_setHALError(status);
+  return retVal;
+}
+
+void SerialPort::SetTimeout(double timeout) {
+  int32_t status = 0;
+  HAL_SetSerialTimeout(m_portHandle, timeout, &status);
+  wpi_setHALError(status);
+}
+
+void SerialPort::SetReadBufferSize(int size) {
+  int32_t status = 0;
+  HAL_SetSerialReadBufferSize(m_portHandle, size, &status);
+  wpi_setHALError(status);
+}
+
+void SerialPort::SetWriteBufferSize(int size) {
+  int32_t status = 0;
+  HAL_SetSerialWriteBufferSize(m_portHandle, size, &status);
+  wpi_setHALError(status);
+}
+
+void SerialPort::SetWriteBufferMode(SerialPort::WriteBufferMode mode) {
+  int32_t status = 0;
+  HAL_SetSerialWriteMode(m_portHandle, mode, &status);
+  wpi_setHALError(status);
+}
+
+void SerialPort::Flush() {
+  int32_t status = 0;
+  HAL_FlushSerial(m_portHandle, &status);
+  wpi_setHALError(status);
+}
+
+void SerialPort::Reset() {
+  int32_t status = 0;
+  HAL_ClearSerial(m_portHandle, &status);
+  wpi_setHALError(status);
+}
diff --git a/wpilibc/src/main/native/cpp/Servo.cpp b/wpilibc/src/main/native/cpp/Servo.cpp
new file mode 100644
index 0000000..4b6856a
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Servo.cpp
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Servo.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+constexpr double Servo::kMaxServoAngle;
+constexpr double Servo::kMinServoAngle;
+
+constexpr double Servo::kDefaultMaxServoPWM;
+constexpr double Servo::kDefaultMinServoPWM;
+
+Servo::Servo(int channel) : PWM(channel) {
+  // Set minimum and maximum PWM values supported by the servo
+  SetBounds(kDefaultMaxServoPWM, 0.0, 0.0, 0.0, kDefaultMinServoPWM);
+
+  // Assign defaults for period multiplier for the servo PWM control signal
+  SetPeriodMultiplier(kPeriodMultiplier_4X);
+
+  HAL_Report(HALUsageReporting::kResourceType_Servo, channel + 1);
+  SendableRegistry::GetInstance().SetName(this, "Servo", channel);
+}
+
+void Servo::Set(double value) { SetPosition(value); }
+
+void Servo::SetOffline() { SetRaw(0); }
+
+double Servo::Get() const { return GetPosition(); }
+
+void Servo::SetAngle(double degrees) {
+  if (degrees < kMinServoAngle) {
+    degrees = kMinServoAngle;
+  } else if (degrees > kMaxServoAngle) {
+    degrees = kMaxServoAngle;
+  }
+
+  SetPosition((degrees - kMinServoAngle) / GetServoAngleRange());
+}
+
+double Servo::GetAngle() const {
+  return GetPosition() * GetServoAngleRange() + kMinServoAngle;
+}
+
+double Servo::GetMaxAngle() const { return kMaxServoAngle; }
+
+double Servo::GetMinAngle() const { return kMinServoAngle; }
+
+void Servo::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Servo");
+  builder.AddDoubleProperty("Value", [=]() { return Get(); },
+                            [=](double value) { Set(value); });
+}
+
+double Servo::GetServoAngleRange() const {
+  return kMaxServoAngle - kMinServoAngle;
+}
diff --git a/wpilibc/src/main/native/cpp/Solenoid.cpp b/wpilibc/src/main/native/cpp/Solenoid.cpp
new file mode 100644
index 0000000..e0bde3c
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Solenoid.cpp
@@ -0,0 +1,98 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Solenoid.h"
+
+#include <utility>
+
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+#include <hal/Ports.h>
+#include <hal/Solenoid.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+Solenoid::Solenoid(int channel)
+    : Solenoid(SensorUtil::GetDefaultSolenoidModule(), channel) {}
+
+Solenoid::Solenoid(int moduleNumber, int channel)
+    : SolenoidBase(moduleNumber), m_channel(channel) {
+  if (!SensorUtil::CheckSolenoidModule(m_moduleNumber)) {
+    wpi_setWPIErrorWithContext(ModuleIndexOutOfRange,
+                               "Solenoid Module " + wpi::Twine(m_moduleNumber));
+    return;
+  }
+  if (!SensorUtil::CheckSolenoidChannel(m_channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
+                               "Solenoid Channel " + wpi::Twine(m_channel));
+    return;
+  }
+
+  int32_t status = 0;
+  m_solenoidHandle = HAL_InitializeSolenoidPort(
+      HAL_GetPortWithModule(moduleNumber, channel), &status);
+  if (status != 0) {
+    wpi_setHALErrorWithRange(status, 0, HAL_GetNumSolenoidChannels(), channel);
+    m_solenoidHandle = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_channel + 1,
+             m_moduleNumber + 1);
+  SendableRegistry::GetInstance().AddLW(this, "Solenoid", m_moduleNumber,
+                                        m_channel);
+}
+
+Solenoid::~Solenoid() { HAL_FreeSolenoidPort(m_solenoidHandle); }
+
+void Solenoid::Set(bool on) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetSolenoid(m_solenoidHandle, on, &status);
+  wpi_setHALError(status);
+}
+
+bool Solenoid::Get() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = HAL_GetSolenoid(m_solenoidHandle, &status);
+  wpi_setHALError(status);
+  return value;
+}
+
+bool Solenoid::IsBlackListed() const {
+  int value = GetPCMSolenoidBlackList(m_moduleNumber) & (1 << m_channel);
+  return (value != 0);
+}
+
+void Solenoid::SetPulseDuration(double durationSeconds) {
+  int32_t durationMS = durationSeconds * 1000;
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetOneShotDuration(m_solenoidHandle, durationMS, &status);
+  wpi_setHALError(status);
+}
+
+void Solenoid::StartPulse() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_FireOneShot(m_solenoidHandle, &status);
+  wpi_setHALError(status);
+}
+
+void Solenoid::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Solenoid");
+  builder.SetActuator(true);
+  builder.SetSafeState([=]() { Set(false); });
+  builder.AddBooleanProperty("Value", [=]() { return Get(); },
+                             [=](bool value) { Set(value); });
+}
diff --git a/wpilibc/src/main/native/cpp/SolenoidBase.cpp b/wpilibc/src/main/native/cpp/SolenoidBase.cpp
new file mode 100644
index 0000000..f5f8aad
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/SolenoidBase.cpp
@@ -0,0 +1,63 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/SolenoidBase.h"
+
+#include <hal/FRCUsageReporting.h>
+#include <hal/Solenoid.h>
+
+using namespace frc;
+
+int SolenoidBase::GetAll(int module) {
+  int value = 0;
+  int32_t status = 0;
+  value = HAL_GetAllSolenoids(module, &status);
+  wpi_setGlobalHALError(status);
+  return value;
+}
+
+int SolenoidBase::GetAll() const {
+  return SolenoidBase::GetAll(m_moduleNumber);
+}
+
+int SolenoidBase::GetPCMSolenoidBlackList(int module) {
+  int32_t status = 0;
+  return HAL_GetPCMSolenoidBlackList(module, &status);
+}
+
+int SolenoidBase::GetPCMSolenoidBlackList() const {
+  return SolenoidBase::GetPCMSolenoidBlackList(m_moduleNumber);
+}
+
+bool SolenoidBase::GetPCMSolenoidVoltageStickyFault(int module) {
+  int32_t status = 0;
+  return HAL_GetPCMSolenoidVoltageStickyFault(module, &status);
+}
+
+bool SolenoidBase::GetPCMSolenoidVoltageStickyFault() const {
+  return SolenoidBase::GetPCMSolenoidVoltageStickyFault(m_moduleNumber);
+}
+
+bool SolenoidBase::GetPCMSolenoidVoltageFault(int module) {
+  int32_t status = 0;
+  return HAL_GetPCMSolenoidVoltageFault(module, &status);
+}
+
+bool SolenoidBase::GetPCMSolenoidVoltageFault() const {
+  return SolenoidBase::GetPCMSolenoidVoltageFault(m_moduleNumber);
+}
+
+void SolenoidBase::ClearAllPCMStickyFaults(int module) {
+  int32_t status = 0;
+  return HAL_ClearAllPCMStickyFaults(module, &status);
+}
+
+void SolenoidBase::ClearAllPCMStickyFaults() {
+  SolenoidBase::ClearAllPCMStickyFaults(m_moduleNumber);
+}
+
+SolenoidBase::SolenoidBase(int moduleNumber) : m_moduleNumber(moduleNumber) {}
diff --git a/wpilibc/src/main/native/cpp/Spark.cpp b/wpilibc/src/main/native/cpp/Spark.cpp
new file mode 100644
index 0000000..3717df4
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Spark.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Spark.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+Spark::Spark(int channel) : PWMSpeedController(channel) {
+  SetBounds(2.003, 1.55, 1.50, 1.46, 0.999);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_RevSPARK, GetChannel() + 1);
+  SendableRegistry::GetInstance().SetName(this, "Spark", GetChannel());
+}
diff --git a/wpilibc/src/main/native/cpp/SpeedController.cpp b/wpilibc/src/main/native/cpp/SpeedController.cpp
new file mode 100644
index 0000000..cb3cc5b
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/SpeedController.cpp
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/SpeedController.h"
+
+#include <frc/RobotController.h>
+
+using namespace frc;
+
+void SpeedController::SetVoltage(units::volt_t output) {
+  Set(output / units::volt_t(RobotController::GetInputVoltage()));
+}
diff --git a/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp b/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp
new file mode 100644
index 0000000..a807afc
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/SpeedControllerGroup.h"
+
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+void SpeedControllerGroup::Set(double speed) {
+  for (auto speedController : m_speedControllers) {
+    speedController.get().Set(m_isInverted ? -speed : speed);
+  }
+}
+
+double SpeedControllerGroup::Get() const {
+  if (!m_speedControllers.empty()) {
+    return m_speedControllers.front().get().Get() * (m_isInverted ? -1 : 1);
+  }
+  return 0.0;
+}
+
+void SpeedControllerGroup::SetInverted(bool isInverted) {
+  m_isInverted = isInverted;
+}
+
+bool SpeedControllerGroup::GetInverted() const { return m_isInverted; }
+
+void SpeedControllerGroup::Disable() {
+  for (auto speedController : m_speedControllers) {
+    speedController.get().Disable();
+  }
+}
+
+void SpeedControllerGroup::StopMotor() {
+  for (auto speedController : m_speedControllers) {
+    speedController.get().StopMotor();
+  }
+}
+
+void SpeedControllerGroup::PIDWrite(double output) { Set(output); }
+
+void SpeedControllerGroup::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Speed Controller");
+  builder.SetActuator(true);
+  builder.SetSafeState([=]() { StopMotor(); });
+  builder.AddDoubleProperty("Value", [=]() { return Get(); },
+                            [=](double value) { Set(value); });
+}
diff --git a/wpilibc/src/main/native/cpp/Talon.cpp b/wpilibc/src/main/native/cpp/Talon.cpp
new file mode 100644
index 0000000..4807d71
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Talon.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Talon.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+Talon::Talon(int channel) : PWMSpeedController(channel) {
+  SetBounds(2.037, 1.539, 1.513, 1.487, 0.989);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_Talon, GetChannel() + 1);
+  SendableRegistry::GetInstance().SetName(this, "Talon", GetChannel());
+}
diff --git a/wpilibc/src/main/native/cpp/Threads.cpp b/wpilibc/src/main/native/cpp/Threads.cpp
new file mode 100644
index 0000000..7b1e647
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Threads.cpp
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Threads.h"
+
+#include <hal/FRCUsageReporting.h>
+#include <hal/Threads.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+int GetThreadPriority(std::thread& thread, bool* isRealTime) {
+  int32_t status = 0;
+  HAL_Bool rt = false;
+  auto native = thread.native_handle();
+  auto ret = HAL_GetThreadPriority(&native, &rt, &status);
+  wpi_setGlobalHALError(status);
+  *isRealTime = rt;
+  return ret;
+}
+
+int GetCurrentThreadPriority(bool* isRealTime) {
+  int32_t status = 0;
+  HAL_Bool rt = false;
+  auto ret = HAL_GetCurrentThreadPriority(&rt, &status);
+  wpi_setGlobalHALError(status);
+  *isRealTime = rt;
+  return ret;
+}
+
+bool SetThreadPriority(std::thread& thread, bool realTime, int priority) {
+  int32_t status = 0;
+  auto native = thread.native_handle();
+  auto ret = HAL_SetThreadPriority(&native, realTime, priority, &status);
+  wpi_setGlobalHALError(status);
+  return ret;
+}
+
+bool SetCurrentThreadPriority(bool realTime, int priority) {
+  int32_t status = 0;
+  auto ret = HAL_SetCurrentThreadPriority(realTime, priority, &status);
+  wpi_setGlobalHALError(status);
+  return ret;
+}
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/cpp/TimedRobot.cpp b/wpilibc/src/main/native/cpp/TimedRobot.cpp
new file mode 100644
index 0000000..a9358dd
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/TimedRobot.cpp
@@ -0,0 +1,83 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/TimedRobot.h"
+
+#include <stdint.h>
+
+#include <utility>
+
+#include <hal/DriverStation.h>
+#include <hal/FRCUsageReporting.h>
+#include <hal/Notifier.h>
+
+#include "frc/Timer.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+void TimedRobot::StartCompetition() {
+  RobotInit();
+
+  // Tell the DS that the robot is ready to be enabled
+  HAL_ObserveUserProgramStarting();
+
+  m_expirationTime = units::second_t{Timer::GetFPGATimestamp()} + m_period;
+  UpdateAlarm();
+
+  // Loop forever, calling the appropriate mode-dependent function
+  while (true) {
+    int32_t status = 0;
+    uint64_t curTime = HAL_WaitForNotifierAlarm(m_notifier, &status);
+    if (curTime == 0 || status != 0) break;
+
+    m_expirationTime += m_period;
+
+    UpdateAlarm();
+
+    // Call callback
+    LoopFunc();
+  }
+}
+
+void TimedRobot::EndCompetition() {
+  int32_t status = 0;
+  HAL_StopNotifier(m_notifier, &status);
+}
+
+units::second_t TimedRobot::GetPeriod() const {
+  return units::second_t(m_period);
+}
+
+TimedRobot::TimedRobot(double period) : TimedRobot(units::second_t(period)) {}
+
+TimedRobot::TimedRobot(units::second_t period) : IterativeRobotBase(period) {
+  int32_t status = 0;
+  m_notifier = HAL_InitializeNotifier(&status);
+  wpi_setHALError(status);
+  HAL_SetNotifierName(m_notifier, "TimedRobot", &status);
+
+  HAL_Report(HALUsageReporting::kResourceType_Framework,
+             HALUsageReporting::kFramework_Timed);
+}
+
+TimedRobot::~TimedRobot() {
+  int32_t status = 0;
+
+  HAL_StopNotifier(m_notifier, &status);
+  wpi_setHALError(status);
+
+  HAL_CleanNotifier(m_notifier, &status);
+}
+
+void TimedRobot::UpdateAlarm() {
+  int32_t status = 0;
+  HAL_UpdateNotifierAlarm(
+      m_notifier, static_cast<uint64_t>(m_expirationTime * 1e6), &status);
+  wpi_setHALError(status);
+}
diff --git a/wpilibc/src/main/native/cpp/Timer.cpp b/wpilibc/src/main/native/cpp/Timer.cpp
new file mode 100644
index 0000000..c91bc13
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Timer.cpp
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Timer.h"
+
+#include <chrono>
+#include <thread>
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/DriverStation.h"
+#include "frc/RobotController.h"
+
+namespace frc {
+
+void Wait(double seconds) { frc2::Wait(units::second_t(seconds)); }
+
+double GetTime() { return frc2::GetTime().to<double>(); }
+
+}  // namespace frc
+
+using namespace frc;
+
+const double Timer::kRolloverTime = frc2::Timer::kRolloverTime.to<double>();
+
+Timer::Timer() { Reset(); }
+
+double Timer::Get() const { return m_timer.Get().to<double>(); }
+
+void Timer::Reset() { m_timer.Reset(); }
+
+void Timer::Start() { m_timer.Start(); }
+
+void Timer::Stop() { m_timer.Stop(); }
+
+bool Timer::HasPeriodPassed(double period) {
+  return m_timer.HasPeriodPassed(units::second_t(period));
+}
+
+double Timer::GetFPGATimestamp() {
+  return frc2::Timer::GetFPGATimestamp().to<double>();
+}
+
+double Timer::GetMatchTime() {
+  return frc2::Timer::GetMatchTime().to<double>();
+}
diff --git a/wpilibc/src/main/native/cpp/Ultrasonic.cpp b/wpilibc/src/main/native/cpp/Ultrasonic.cpp
new file mode 100644
index 0000000..fcd016e
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Ultrasonic.cpp
@@ -0,0 +1,223 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Ultrasonic.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/Counter.h"
+#include "frc/DigitalInput.h"
+#include "frc/DigitalOutput.h"
+#include "frc/Timer.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+// Automatic round robin mode
+std::atomic<bool> Ultrasonic::m_automaticEnabled{false};
+
+std::vector<Ultrasonic*> Ultrasonic::m_sensors;
+std::thread Ultrasonic::m_thread;
+
+Ultrasonic::Ultrasonic(int pingChannel, int echoChannel, DistanceUnit units)
+    : m_pingChannel(std::make_shared<DigitalOutput>(pingChannel)),
+      m_echoChannel(std::make_shared<DigitalInput>(echoChannel)),
+      m_counter(m_echoChannel) {
+  m_units = units;
+  Initialize();
+  auto& registry = SendableRegistry::GetInstance();
+  registry.AddChild(this, m_pingChannel.get());
+  registry.AddChild(this, m_echoChannel.get());
+}
+
+Ultrasonic::Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel,
+                       DistanceUnit units)
+    : m_pingChannel(pingChannel, NullDeleter<DigitalOutput>()),
+      m_echoChannel(echoChannel, NullDeleter<DigitalInput>()),
+      m_counter(m_echoChannel) {
+  if (pingChannel == nullptr || echoChannel == nullptr) {
+    wpi_setWPIError(NullParameter);
+    m_units = units;
+    return;
+  }
+  m_units = units;
+  Initialize();
+}
+
+Ultrasonic::Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel,
+                       DistanceUnit units)
+    : m_pingChannel(&pingChannel, NullDeleter<DigitalOutput>()),
+      m_echoChannel(&echoChannel, NullDeleter<DigitalInput>()),
+      m_counter(m_echoChannel) {
+  m_units = units;
+  Initialize();
+}
+
+Ultrasonic::Ultrasonic(std::shared_ptr<DigitalOutput> pingChannel,
+                       std::shared_ptr<DigitalInput> echoChannel,
+                       DistanceUnit units)
+    : m_pingChannel(pingChannel),
+      m_echoChannel(echoChannel),
+      m_counter(m_echoChannel) {
+  m_units = units;
+  Initialize();
+}
+
+Ultrasonic::~Ultrasonic() {
+  // Delete the instance of the ultrasonic sensor by freeing the allocated
+  // digital channels. If the system was in automatic mode (round robin), then
+  // it is stopped, then started again after this sensor is removed (provided
+  // this wasn't the last sensor).
+
+  bool wasAutomaticMode = m_automaticEnabled;
+  SetAutomaticMode(false);
+
+  // No synchronization needed because the background task is stopped.
+  m_sensors.erase(std::remove(m_sensors.begin(), m_sensors.end(), this),
+                  m_sensors.end());
+
+  if (!m_sensors.empty() && wasAutomaticMode) {
+    SetAutomaticMode(true);
+  }
+}
+
+void Ultrasonic::Ping() {
+  wpi_assert(!m_automaticEnabled);
+
+  // Reset the counter to zero (invalid data now)
+  m_counter.Reset();
+
+  // Do the ping to start getting a single range
+  m_pingChannel->Pulse(kPingTime);
+}
+
+bool Ultrasonic::IsRangeValid() const {
+  if (m_simRangeValid) return m_simRangeValid.Get();
+  return m_counter.Get() > 1;
+}
+
+void Ultrasonic::SetAutomaticMode(bool enabling) {
+  if (enabling == m_automaticEnabled) return;  // ignore the case of no change
+
+  m_automaticEnabled = enabling;
+
+  if (enabling) {
+    /* Clear all the counters so no data is valid. No synchronization is needed
+     * because the background task is stopped.
+     */
+    for (auto& sensor : m_sensors) {
+      sensor->m_counter.Reset();
+    }
+
+    m_thread = std::thread(&Ultrasonic::UltrasonicChecker);
+
+    // TODO: Currently, lvuser does not have permissions to set task priorities.
+    // Until that is the case, uncommenting this will break user code that calls
+    // Ultrasonic::SetAutomicMode().
+    // m_task.SetPriority(kPriority);
+  } else {
+    // Wait for background task to stop running
+    if (m_thread.joinable()) {
+      m_thread.join();
+    }
+
+    // Clear all the counters (data now invalid) since automatic mode is
+    // disabled. No synchronization is needed because the background task is
+    // stopped.
+    for (auto& sensor : m_sensors) {
+      sensor->m_counter.Reset();
+    }
+  }
+}
+
+double Ultrasonic::GetRangeInches() const {
+  if (IsRangeValid()) {
+    if (m_simRange) return m_simRange.Get();
+    return m_counter.GetPeriod() * kSpeedOfSoundInchesPerSec / 2.0;
+  } else {
+    return 0;
+  }
+}
+
+double Ultrasonic::GetRangeMM() const { return GetRangeInches() * 25.4; }
+
+bool Ultrasonic::IsEnabled() const { return m_enabled; }
+
+void Ultrasonic::SetEnabled(bool enable) { m_enabled = enable; }
+
+void Ultrasonic::SetDistanceUnits(DistanceUnit units) { m_units = units; }
+
+Ultrasonic::DistanceUnit Ultrasonic::GetDistanceUnits() const {
+  return m_units;
+}
+
+double Ultrasonic::PIDGet() {
+  switch (m_units) {
+    case Ultrasonic::kInches:
+      return GetRangeInches();
+    case Ultrasonic::kMilliMeters:
+      return GetRangeMM();
+    default:
+      return 0.0;
+  }
+}
+
+void Ultrasonic::SetPIDSourceType(PIDSourceType pidSource) {
+  if (wpi_assert(pidSource == PIDSourceType::kDisplacement)) {
+    m_pidSource = pidSource;
+  }
+}
+
+void Ultrasonic::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Ultrasonic");
+  builder.AddDoubleProperty("Value", [=]() { return GetRangeInches(); },
+                            nullptr);
+}
+
+void Ultrasonic::Initialize() {
+  m_simDevice = hal::SimDevice("Ultrasonic", m_echoChannel->GetChannel());
+  if (m_simDevice) {
+    m_simRangeValid = m_simDevice.CreateBoolean("Range Valid", false, true);
+    m_simRange = m_simDevice.CreateDouble("Range (in)", false, 0.0);
+    m_pingChannel->SetSimDevice(m_simDevice);
+    m_echoChannel->SetSimDevice(m_simDevice);
+  }
+
+  bool originalMode = m_automaticEnabled;
+  SetAutomaticMode(false);  // Kill task when adding a new sensor
+  // Link this instance on the list
+  m_sensors.emplace_back(this);
+
+  m_counter.SetMaxPeriod(1.0);
+  m_counter.SetSemiPeriodMode(true);
+  m_counter.Reset();
+  m_enabled = true;  // Make it available for round robin scheduling
+  SetAutomaticMode(originalMode);
+
+  static int instances = 0;
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_Ultrasonic, instances);
+  SendableRegistry::GetInstance().AddLW(this, "Ultrasonic",
+                                        m_echoChannel->GetChannel());
+}
+
+void Ultrasonic::UltrasonicChecker() {
+  while (m_automaticEnabled) {
+    for (auto& sensor : m_sensors) {
+      if (!m_automaticEnabled) break;
+
+      if (sensor->IsEnabled()) {
+        sensor->m_pingChannel->Pulse(kPingTime);  // do the ping
+      }
+
+      Wait(0.1);  // wait for ping to return
+    }
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/Utility.cpp b/wpilibc/src/main/native/cpp/Utility.cpp
new file mode 100644
index 0000000..11f6234
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Utility.cpp
@@ -0,0 +1,118 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Utility.h"
+
+#ifndef _WIN32
+#include <cxxabi.h>
+#include <execinfo.h>
+#endif
+
+#include <cstdio>
+#include <cstdlib>
+#include <cstring>
+
+#include <hal/DriverStation.h>
+#include <hal/FRCUsageReporting.h>
+#include <wpi/Path.h>
+#include <wpi/SmallString.h>
+#include <wpi/StackTrace.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/ErrorBase.h"
+
+using namespace frc;
+
+bool wpi_assert_impl(bool conditionValue, const wpi::Twine& conditionText,
+                     const wpi::Twine& message, wpi::StringRef fileName,
+                     int lineNumber, wpi::StringRef funcName) {
+  if (!conditionValue) {
+    wpi::SmallString<128> locBuf;
+    wpi::raw_svector_ostream locStream(locBuf);
+    locStream << funcName << " [" << wpi::sys::path::filename(fileName) << ":"
+              << lineNumber << "]";
+
+    wpi::SmallString<128> errorBuf;
+    wpi::raw_svector_ostream errorStream(errorBuf);
+
+    errorStream << "Assertion \"" << conditionText << "\" ";
+
+    if (message.isTriviallyEmpty() ||
+        (message.isSingleStringRef() && message.getSingleStringRef().empty())) {
+      errorStream << "failed.\n";
+    } else {
+      errorStream << "failed: " << message << "\n";
+    }
+
+    std::string stack = wpi::GetStackTrace(2);
+
+    // Print the error and send it to the DriverStation
+    HAL_SendError(1, 1, 0, errorBuf.c_str(), locBuf.c_str(), stack.c_str(), 1);
+  }
+
+  return conditionValue;
+}
+
+/**
+ * Common error routines for wpi_assertEqual_impl and wpi_assertNotEqual_impl.
+ *
+ * This should not be called directly; it should only be used by
+ * wpi_assertEqual_impl and wpi_assertNotEqual_impl.
+ */
+void wpi_assertEqual_common_impl(const wpi::Twine& valueA,
+                                 const wpi::Twine& valueB,
+                                 const wpi::Twine& equalityType,
+                                 const wpi::Twine& message,
+                                 wpi::StringRef fileName, int lineNumber,
+                                 wpi::StringRef funcName) {
+  wpi::SmallString<128> locBuf;
+  wpi::raw_svector_ostream locStream(locBuf);
+  locStream << funcName << " [" << wpi::sys::path::filename(fileName) << ":"
+            << lineNumber << "]";
+
+  wpi::SmallString<128> errorBuf;
+  wpi::raw_svector_ostream errorStream(errorBuf);
+
+  errorStream << "Assertion \"" << valueA << " " << equalityType << " "
+              << valueB << "\" ";
+
+  if (message.isTriviallyEmpty() ||
+      (message.isSingleStringRef() && message.getSingleStringRef().empty())) {
+    errorStream << "failed.\n";
+  } else {
+    errorStream << "failed: " << message << "\n";
+  }
+
+  std::string trace = wpi::GetStackTrace(3);
+
+  // Print the error and send it to the DriverStation
+  HAL_SendError(1, 1, 0, errorBuf.c_str(), locBuf.c_str(), trace.c_str(), 1);
+}
+
+bool wpi_assertEqual_impl(int valueA, int valueB,
+                          const wpi::Twine& valueAString,
+                          const wpi::Twine& valueBString,
+                          const wpi::Twine& message, wpi::StringRef fileName,
+                          int lineNumber, wpi::StringRef funcName) {
+  if (!(valueA == valueB)) {
+    wpi_assertEqual_common_impl(valueAString, valueBString, "==", message,
+                                fileName, lineNumber, funcName);
+  }
+  return valueA == valueB;
+}
+
+bool wpi_assertNotEqual_impl(int valueA, int valueB,
+                             const wpi::Twine& valueAString,
+                             const wpi::Twine& valueBString,
+                             const wpi::Twine& message, wpi::StringRef fileName,
+                             int lineNumber, wpi::StringRef funcName) {
+  if (!(valueA != valueB)) {
+    wpi_assertEqual_common_impl(valueAString, valueBString, "!=", message,
+                                fileName, lineNumber, funcName);
+  }
+  return valueA != valueB;
+}
diff --git a/wpilibc/src/main/native/cpp/Victor.cpp b/wpilibc/src/main/native/cpp/Victor.cpp
new file mode 100644
index 0000000..bce1913
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Victor.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Victor.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+Victor::Victor(int channel) : PWMSpeedController(channel) {
+  SetBounds(2.027, 1.525, 1.507, 1.49, 1.026);
+  SetPeriodMultiplier(kPeriodMultiplier_2X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_Victor, GetChannel() + 1);
+  SendableRegistry::GetInstance().SetName(this, "Victor", GetChannel());
+}
diff --git a/wpilibc/src/main/native/cpp/VictorSP.cpp b/wpilibc/src/main/native/cpp/VictorSP.cpp
new file mode 100644
index 0000000..221777d
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/VictorSP.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/VictorSP.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+VictorSP::VictorSP(int channel) : PWMSpeedController(channel) {
+  SetBounds(2.004, 1.52, 1.50, 1.48, 0.997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_VictorSP, GetChannel() + 1);
+  SendableRegistry::GetInstance().SetName(this, "VictorSP", GetChannel());
+}
diff --git a/wpilibc/src/main/native/cpp/Watchdog.cpp b/wpilibc/src/main/native/cpp/Watchdog.cpp
new file mode 100644
index 0000000..e5be4fa
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/Watchdog.cpp
@@ -0,0 +1,193 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Watchdog.h"
+
+#include <wpi/Format.h>
+#include <wpi/PriorityQueue.h>
+#include <wpi/raw_ostream.h>
+
+using namespace frc;
+
+constexpr std::chrono::milliseconds Watchdog::kMinPrintPeriod;
+
+class Watchdog::Thread : public wpi::SafeThread {
+ public:
+  template <typename T>
+  struct DerefGreater {
+    constexpr bool operator()(const T& lhs, const T& rhs) const {
+      return *lhs > *rhs;
+    }
+  };
+
+  wpi::PriorityQueue<Watchdog*, std::vector<Watchdog*>, DerefGreater<Watchdog*>>
+      m_watchdogs;
+
+ private:
+  void Main() override;
+};
+
+void Watchdog::Thread::Main() {
+  std::unique_lock lock(m_mutex);
+
+  while (m_active) {
+    if (m_watchdogs.size() > 0) {
+      if (m_cond.wait_until(lock, m_watchdogs.top()->m_expirationTime) ==
+          std::cv_status::timeout) {
+        if (m_watchdogs.size() == 0 ||
+            m_watchdogs.top()->m_expirationTime > hal::fpga_clock::now()) {
+          continue;
+        }
+
+        // If the condition variable timed out, that means a Watchdog timeout
+        // has occurred, so call its timeout function.
+        auto watchdog = m_watchdogs.top();
+        m_watchdogs.pop();
+
+        auto now = hal::fpga_clock::now();
+        if (now - watchdog->m_lastTimeoutPrintTime > kMinPrintPeriod) {
+          watchdog->m_lastTimeoutPrintTime = now;
+          if (!watchdog->m_suppressTimeoutMessage) {
+            wpi::outs() << "Watchdog not fed within "
+                        << wpi::format("%.6f",
+                                       watchdog->m_timeout.count() / 1.0e9)
+                        << "s\n";
+          }
+        }
+
+        // Set expiration flag before calling the callback so any manipulation
+        // of the flag in the callback (e.g., calling Disable()) isn't
+        // clobbered.
+        watchdog->m_isExpired = true;
+
+        lock.unlock();
+        watchdog->m_callback();
+        lock.lock();
+      }
+      // Otherwise, a Watchdog removed itself from the queue (it notifies the
+      // scheduler of this) or a spurious wakeup occurred, so just rewait with
+      // the soonest watchdog timeout.
+    } else {
+      m_cond.wait(lock, [&] { return m_watchdogs.size() > 0 || !m_active; });
+    }
+  }
+}
+
+Watchdog::Watchdog(double timeout, std::function<void()> callback)
+    : Watchdog(units::second_t{timeout}, callback) {}
+
+Watchdog::Watchdog(units::second_t timeout, std::function<void()> callback)
+    : m_timeout(timeout), m_callback(callback), m_owner(&GetThreadOwner()) {}
+
+Watchdog::~Watchdog() { Disable(); }
+
+double Watchdog::GetTime() const {
+  return (hal::fpga_clock::now() - m_startTime).count() / 1.0e6;
+}
+
+void Watchdog::SetTimeout(double timeout) {
+  SetTimeout(units::second_t{timeout});
+}
+
+void Watchdog::SetTimeout(units::second_t timeout) {
+  using std::chrono::duration_cast;
+  using std::chrono::microseconds;
+
+  m_startTime = hal::fpga_clock::now();
+  m_epochs.clear();
+
+  // Locks mutex
+  auto thr = m_owner->GetThread();
+  if (!thr) return;
+
+  m_timeout = timeout;
+  m_isExpired = false;
+
+  thr->m_watchdogs.remove(this);
+  m_expirationTime = m_startTime + duration_cast<microseconds>(m_timeout);
+  thr->m_watchdogs.emplace(this);
+  thr->m_cond.notify_all();
+}
+
+double Watchdog::GetTimeout() const {
+  // Locks mutex
+  auto thr = m_owner->GetThread();
+
+  return m_timeout.count() / 1.0e9;
+}
+
+bool Watchdog::IsExpired() const {
+  // Locks mutex
+  auto thr = m_owner->GetThread();
+
+  return m_isExpired;
+}
+
+void Watchdog::AddEpoch(wpi::StringRef epochName) {
+  auto currentTime = hal::fpga_clock::now();
+  m_epochs[epochName] = currentTime - m_startTime;
+  m_startTime = currentTime;
+}
+
+void Watchdog::PrintEpochs() {
+  auto now = hal::fpga_clock::now();
+  if (now - m_lastEpochsPrintTime > kMinPrintPeriod) {
+    m_lastEpochsPrintTime = now;
+    for (const auto& epoch : m_epochs) {
+      wpi::outs() << '\t' << epoch.getKey() << ": "
+                  << wpi::format("%.6f", epoch.getValue().count() / 1.0e6)
+                  << "s\n";
+    }
+  }
+}
+
+void Watchdog::Reset() { Enable(); }
+
+void Watchdog::Enable() {
+  using std::chrono::duration_cast;
+  using std::chrono::microseconds;
+
+  m_startTime = hal::fpga_clock::now();
+  m_epochs.clear();
+
+  // Locks mutex
+  auto thr = m_owner->GetThread();
+  if (!thr) return;
+
+  m_isExpired = false;
+
+  thr->m_watchdogs.remove(this);
+  m_expirationTime = m_startTime + duration_cast<microseconds>(m_timeout);
+  thr->m_watchdogs.emplace(this);
+  thr->m_cond.notify_all();
+}
+
+void Watchdog::Disable() {
+  // Locks mutex
+  auto thr = m_owner->GetThread();
+  if (!thr) return;
+
+  thr->m_watchdogs.remove(this);
+  thr->m_cond.notify_all();
+}
+
+void Watchdog::SuppressTimeoutMessage(bool suppress) {
+  m_suppressTimeoutMessage = suppress;
+}
+
+bool Watchdog::operator>(const Watchdog& rhs) {
+  return m_expirationTime > rhs.m_expirationTime;
+}
+
+wpi::SafeThreadOwner<Watchdog::Thread>& Watchdog::GetThreadOwner() {
+  static wpi::SafeThreadOwner<Thread> inst = [] {
+    wpi::SafeThreadOwner<Watchdog::Thread> inst;
+    inst.Start();
+    return inst;
+  }();
+  return inst;
+}
diff --git a/wpilibc/src/main/native/cpp/XboxController.cpp b/wpilibc/src/main/native/cpp/XboxController.cpp
new file mode 100644
index 0000000..b294257
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/XboxController.cpp
@@ -0,0 +1,160 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/XboxController.h"
+
+#include <hal/FRCUsageReporting.h>
+
+using namespace frc;
+
+XboxController::XboxController(int port) : GenericHID(port) {
+  HAL_Report(HALUsageReporting::kResourceType_XboxController, port + 1);
+}
+
+double XboxController::GetX(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawAxis(0);
+  } else {
+    return GetRawAxis(4);
+  }
+}
+
+double XboxController::GetY(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawAxis(1);
+  } else {
+    return GetRawAxis(5);
+  }
+}
+
+double XboxController::GetTriggerAxis(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawAxis(2);
+  } else {
+    return GetRawAxis(3);
+  }
+}
+
+bool XboxController::GetBumper(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawButton(static_cast<int>(Button::kBumperLeft));
+  } else {
+    return GetRawButton(static_cast<int>(Button::kBumperRight));
+  }
+}
+
+bool XboxController::GetBumperPressed(JoystickHand hand) {
+  if (hand == kLeftHand) {
+    return GetRawButtonPressed(static_cast<int>(Button::kBumperLeft));
+  } else {
+    return GetRawButtonPressed(static_cast<int>(Button::kBumperRight));
+  }
+}
+
+bool XboxController::GetBumperReleased(JoystickHand hand) {
+  if (hand == kLeftHand) {
+    return GetRawButtonReleased(static_cast<int>(Button::kBumperLeft));
+  } else {
+    return GetRawButtonReleased(static_cast<int>(Button::kBumperRight));
+  }
+}
+
+bool XboxController::GetStickButton(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawButton(static_cast<int>(Button::kStickLeft));
+  } else {
+    return GetRawButton(static_cast<int>(Button::kStickRight));
+  }
+}
+
+bool XboxController::GetStickButtonPressed(JoystickHand hand) {
+  if (hand == kLeftHand) {
+    return GetRawButtonPressed(static_cast<int>(Button::kStickLeft));
+  } else {
+    return GetRawButtonPressed(static_cast<int>(Button::kStickRight));
+  }
+}
+
+bool XboxController::GetStickButtonReleased(JoystickHand hand) {
+  if (hand == kLeftHand) {
+    return GetRawButtonReleased(static_cast<int>(Button::kStickLeft));
+  } else {
+    return GetRawButtonReleased(static_cast<int>(Button::kStickRight));
+  }
+}
+
+bool XboxController::GetAButton() const {
+  return GetRawButton(static_cast<int>(Button::kA));
+}
+
+bool XboxController::GetAButtonPressed() {
+  return GetRawButtonPressed(static_cast<int>(Button::kA));
+}
+
+bool XboxController::GetAButtonReleased() {
+  return GetRawButtonReleased(static_cast<int>(Button::kA));
+}
+
+bool XboxController::GetBButton() const {
+  return GetRawButton(static_cast<int>(Button::kB));
+}
+
+bool XboxController::GetBButtonPressed() {
+  return GetRawButtonPressed(static_cast<int>(Button::kB));
+}
+
+bool XboxController::GetBButtonReleased() {
+  return GetRawButtonReleased(static_cast<int>(Button::kB));
+}
+
+bool XboxController::GetXButton() const {
+  return GetRawButton(static_cast<int>(Button::kX));
+}
+
+bool XboxController::GetXButtonPressed() {
+  return GetRawButtonPressed(static_cast<int>(Button::kX));
+}
+
+bool XboxController::GetXButtonReleased() {
+  return GetRawButtonReleased(static_cast<int>(Button::kX));
+}
+
+bool XboxController::GetYButton() const {
+  return GetRawButton(static_cast<int>(Button::kY));
+}
+
+bool XboxController::GetYButtonPressed() {
+  return GetRawButtonPressed(static_cast<int>(Button::kY));
+}
+
+bool XboxController::GetYButtonReleased() {
+  return GetRawButtonReleased(static_cast<int>(Button::kY));
+}
+
+bool XboxController::GetBackButton() const {
+  return GetRawButton(static_cast<int>(Button::kBack));
+}
+
+bool XboxController::GetBackButtonPressed() {
+  return GetRawButtonPressed(static_cast<int>(Button::kBack));
+}
+
+bool XboxController::GetBackButtonReleased() {
+  return GetRawButtonReleased(static_cast<int>(Button::kBack));
+}
+
+bool XboxController::GetStartButton() const {
+  return GetRawButton(static_cast<int>(Button::kStart));
+}
+
+bool XboxController::GetStartButtonPressed() {
+  return GetRawButtonPressed(static_cast<int>(Button::kStart));
+}
+
+bool XboxController::GetStartButtonReleased() {
+  return GetRawButtonReleased(static_cast<int>(Button::kStart));
+}
diff --git a/wpilibc/src/main/native/cpp/controller/PIDController.cpp b/wpilibc/src/main/native/cpp/controller/PIDController.cpp
new file mode 100644
index 0000000..3abd4ba
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/controller/PIDController.cpp
@@ -0,0 +1,147 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/controller/PIDController.h"
+
+#include <algorithm>
+#include <cmath>
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc2;
+
+PIDController::PIDController(double Kp, double Ki, double Kd,
+                             units::second_t period)
+    : m_Kp(Kp), m_Ki(Ki), m_Kd(Kd), m_period(period) {
+  static int instances = 0;
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_PIDController2, instances);
+  frc::SendableRegistry::GetInstance().Add(this, "PIDController", instances);
+}
+
+void PIDController::SetP(double Kp) { m_Kp = Kp; }
+
+void PIDController::SetI(double Ki) { m_Ki = Ki; }
+
+void PIDController::SetD(double Kd) { m_Kd = Kd; }
+
+double PIDController::GetP() const { return m_Kp; }
+
+double PIDController::GetI() const { return m_Ki; }
+
+double PIDController::GetD() const { return m_Kd; }
+
+units::second_t PIDController::GetPeriod() const {
+  return units::second_t(m_period);
+}
+
+void PIDController::SetSetpoint(double setpoint) {
+  if (m_maximumInput > m_minimumInput) {
+    m_setpoint = std::clamp(setpoint, m_minimumInput, m_maximumInput);
+  } else {
+    m_setpoint = setpoint;
+  }
+}
+
+double PIDController::GetSetpoint() const { return m_setpoint; }
+
+bool PIDController::AtSetpoint() const {
+  return std::abs(m_positionError) < m_positionTolerance &&
+         std::abs(m_velocityError) < m_velocityTolerance;
+}
+
+void PIDController::EnableContinuousInput(double minimumInput,
+                                          double maximumInput) {
+  m_continuous = true;
+  SetInputRange(minimumInput, maximumInput);
+}
+
+void PIDController::DisableContinuousInput() { m_continuous = false; }
+
+void PIDController::SetIntegratorRange(double minimumIntegral,
+                                       double maximumIntegral) {
+  m_minimumIntegral = minimumIntegral;
+  m_maximumIntegral = maximumIntegral;
+}
+
+void PIDController::SetTolerance(double positionTolerance,
+                                 double velocityTolerance) {
+  m_positionTolerance = positionTolerance;
+  m_velocityTolerance = velocityTolerance;
+}
+
+double PIDController::GetPositionError() const {
+  return GetContinuousError(m_positionError);
+}
+
+double PIDController::GetVelocityError() const { return m_velocityError; }
+
+double PIDController::Calculate(double measurement) {
+  m_prevError = m_positionError;
+  m_positionError = GetContinuousError(m_setpoint - measurement);
+  m_velocityError = (m_positionError - m_prevError) / m_period.to<double>();
+
+  if (m_Ki != 0) {
+    m_totalError =
+        std::clamp(m_totalError + m_positionError * m_period.to<double>(),
+                   m_minimumIntegral / m_Ki, m_maximumIntegral / m_Ki);
+  }
+
+  return m_Kp * m_positionError + m_Ki * m_totalError + m_Kd * m_velocityError;
+}
+
+double PIDController::Calculate(double measurement, double setpoint) {
+  // Set setpoint to provided value
+  SetSetpoint(setpoint);
+  return Calculate(measurement);
+}
+
+void PIDController::Reset() {
+  m_prevError = 0;
+  m_totalError = 0;
+}
+
+void PIDController::InitSendable(frc::SendableBuilder& builder) {
+  builder.SetSmartDashboardType("PIDController");
+  builder.AddDoubleProperty("p", [this] { return GetP(); },
+                            [this](double value) { SetP(value); });
+  builder.AddDoubleProperty("i", [this] { return GetI(); },
+                            [this](double value) { SetI(value); });
+  builder.AddDoubleProperty("d", [this] { return GetD(); },
+                            [this](double value) { SetD(value); });
+  builder.AddDoubleProperty("setpoint", [this] { return GetSetpoint(); },
+                            [this](double value) { SetSetpoint(value); });
+}
+
+double PIDController::GetContinuousError(double error) const {
+  if (m_continuous && m_inputRange > 0) {
+    error = std::fmod(error, m_inputRange);
+    if (std::abs(error) > m_inputRange / 2) {
+      if (error > 0) {
+        return error - m_inputRange;
+      } else {
+        return error + m_inputRange;
+      }
+    }
+  }
+
+  return error;
+}
+
+void PIDController::SetInputRange(double minimumInput, double maximumInput) {
+  m_minimumInput = minimumInput;
+  m_maximumInput = maximumInput;
+  m_inputRange = maximumInput - minimumInput;
+
+  // Clamp setpoint to new input range
+  if (m_maximumInput > m_minimumInput) {
+    m_setpoint = std::clamp(m_setpoint, m_minimumInput, m_maximumInput);
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/controller/ProfiledPIDController.cpp b/wpilibc/src/main/native/cpp/controller/ProfiledPIDController.cpp
new file mode 100644
index 0000000..a0fffc6
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/controller/ProfiledPIDController.cpp
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/controller/ProfiledPIDController.h"
+
+#include <hal/FRCUsageReporting.h>
+
+void frc::detail::ReportProfiledPIDController() {
+  static int instances = 0;
+  ++instances;
+  HAL_Report(HALUsageReporting::kResourceType_ProfiledPIDController, instances);
+}
diff --git a/wpilibc/src/main/native/cpp/controller/RamseteController.cpp b/wpilibc/src/main/native/cpp/controller/RamseteController.cpp
new file mode 100644
index 0000000..c55c2e8
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/controller/RamseteController.cpp
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/controller/RamseteController.h"
+
+#include <cmath>
+
+using namespace frc;
+
+/**
+ * Returns sin(x) / x.
+ *
+ * @param x Value of which to take sinc(x).
+ */
+static double Sinc(double x) {
+  if (std::abs(x) < 1e-9) {
+    return 1.0 - 1.0 / 6.0 * x * x;
+  } else {
+    return std::sin(x) / x;
+  }
+}
+
+RamseteController::RamseteController(double b, double zeta)
+    : m_b{b}, m_zeta{zeta} {}
+
+bool RamseteController::AtReference() const {
+  const auto& eTranslate = m_poseError.Translation();
+  const auto& eRotate = m_poseError.Rotation();
+  const auto& tolTranslate = m_poseTolerance.Translation();
+  const auto& tolRotate = m_poseTolerance.Rotation();
+  return units::math::abs(eTranslate.X()) < tolTranslate.X() &&
+         units::math::abs(eTranslate.Y()) < tolTranslate.Y() &&
+         units::math::abs(eRotate.Radians()) < tolRotate.Radians();
+}
+
+void RamseteController::SetTolerance(const Pose2d& poseTolerance) {
+  m_poseTolerance = poseTolerance;
+}
+
+ChassisSpeeds RamseteController::Calculate(
+    const Pose2d& currentPose, const Pose2d& poseRef,
+    units::meters_per_second_t linearVelocityRef,
+    units::radians_per_second_t angularVelocityRef) {
+  m_poseError = poseRef.RelativeTo(currentPose);
+
+  // Aliases for equation readability
+  double eX = m_poseError.Translation().X().to<double>();
+  double eY = m_poseError.Translation().Y().to<double>();
+  double eTheta = m_poseError.Rotation().Radians().to<double>();
+  double vRef = linearVelocityRef.to<double>();
+  double omegaRef = angularVelocityRef.to<double>();
+
+  double k =
+      2.0 * m_zeta * std::sqrt(std::pow(omegaRef, 2) + m_b * std::pow(vRef, 2));
+
+  units::meters_per_second_t v{vRef * m_poseError.Rotation().Cos() + k * eX};
+  units::radians_per_second_t omega{omegaRef + k * eTheta +
+                                    m_b * vRef * Sinc(eTheta) * eY};
+  return ChassisSpeeds{v, 0_mps, omega};
+}
+
+ChassisSpeeds RamseteController::Calculate(
+    const Pose2d& currentPose, const Trajectory::State& desiredState) {
+  return Calculate(currentPose, desiredState.pose, desiredState.velocity,
+                   desiredState.velocity * desiredState.curvature);
+}
diff --git a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp
new file mode 100644
index 0000000..2d30a2b
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp
@@ -0,0 +1,228 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/drive/DifferentialDrive.h"
+
+#include <algorithm>
+#include <cmath>
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/SpeedController.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+DifferentialDrive::DifferentialDrive(SpeedController& leftMotor,
+                                     SpeedController& rightMotor)
+    : m_leftMotor(&leftMotor), m_rightMotor(&rightMotor) {
+  auto& registry = SendableRegistry::GetInstance();
+  registry.AddChild(this, m_leftMotor);
+  registry.AddChild(this, m_rightMotor);
+  static int instances = 0;
+  ++instances;
+  registry.AddLW(this, "DifferentialDrive", instances);
+}
+
+void DifferentialDrive::ArcadeDrive(double xSpeed, double zRotation,
+                                    bool squareInputs) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
+               HALUsageReporting::kRobotDrive2_DifferentialArcade, 2);
+    reported = true;
+  }
+
+  xSpeed = std::clamp(xSpeed, -1.0, 1.0);
+  xSpeed = ApplyDeadband(xSpeed, m_deadband);
+
+  zRotation = std::clamp(zRotation, -1.0, 1.0);
+  zRotation = ApplyDeadband(zRotation, m_deadband);
+
+  // Square the inputs (while preserving the sign) to increase fine control
+  // while permitting full power.
+  if (squareInputs) {
+    xSpeed = std::copysign(xSpeed * xSpeed, xSpeed);
+    zRotation = std::copysign(zRotation * zRotation, zRotation);
+  }
+
+  double leftMotorOutput;
+  double rightMotorOutput;
+
+  double maxInput =
+      std::copysign(std::max(std::abs(xSpeed), std::abs(zRotation)), xSpeed);
+
+  if (xSpeed >= 0.0) {
+    // First quadrant, else second quadrant
+    if (zRotation >= 0.0) {
+      leftMotorOutput = maxInput;
+      rightMotorOutput = xSpeed - zRotation;
+    } else {
+      leftMotorOutput = xSpeed + zRotation;
+      rightMotorOutput = maxInput;
+    }
+  } else {
+    // Third quadrant, else fourth quadrant
+    if (zRotation >= 0.0) {
+      leftMotorOutput = xSpeed + zRotation;
+      rightMotorOutput = maxInput;
+    } else {
+      leftMotorOutput = maxInput;
+      rightMotorOutput = xSpeed - zRotation;
+    }
+  }
+
+  m_leftMotor->Set(std::clamp(leftMotorOutput, -1.0, 1.0) * m_maxOutput);
+  double maxOutput = m_maxOutput * m_rightSideInvertMultiplier;
+  m_rightMotor->Set(std::clamp(rightMotorOutput, -1.0, 1.0) * maxOutput);
+
+  Feed();
+}
+
+void DifferentialDrive::CurvatureDrive(double xSpeed, double zRotation,
+                                       bool isQuickTurn) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
+               HALUsageReporting::kRobotDrive2_DifferentialCurvature, 2);
+    reported = true;
+  }
+
+  xSpeed = std::clamp(xSpeed, -1.0, 1.0);
+  xSpeed = ApplyDeadband(xSpeed, m_deadband);
+
+  zRotation = std::clamp(zRotation, -1.0, 1.0);
+  zRotation = ApplyDeadband(zRotation, m_deadband);
+
+  double angularPower;
+  bool overPower;
+
+  if (isQuickTurn) {
+    if (std::abs(xSpeed) < m_quickStopThreshold) {
+      m_quickStopAccumulator =
+          (1 - m_quickStopAlpha) * m_quickStopAccumulator +
+          m_quickStopAlpha * std::clamp(zRotation, -1.0, 1.0) * 2;
+    }
+    overPower = true;
+    angularPower = zRotation;
+  } else {
+    overPower = false;
+    angularPower = std::abs(xSpeed) * zRotation - m_quickStopAccumulator;
+
+    if (m_quickStopAccumulator > 1) {
+      m_quickStopAccumulator -= 1;
+    } else if (m_quickStopAccumulator < -1) {
+      m_quickStopAccumulator += 1;
+    } else {
+      m_quickStopAccumulator = 0.0;
+    }
+  }
+
+  double leftMotorOutput = xSpeed + angularPower;
+  double rightMotorOutput = xSpeed - angularPower;
+
+  // If rotation is overpowered, reduce both outputs to within acceptable range
+  if (overPower) {
+    if (leftMotorOutput > 1.0) {
+      rightMotorOutput -= leftMotorOutput - 1.0;
+      leftMotorOutput = 1.0;
+    } else if (rightMotorOutput > 1.0) {
+      leftMotorOutput -= rightMotorOutput - 1.0;
+      rightMotorOutput = 1.0;
+    } else if (leftMotorOutput < -1.0) {
+      rightMotorOutput -= leftMotorOutput + 1.0;
+      leftMotorOutput = -1.0;
+    } else if (rightMotorOutput < -1.0) {
+      leftMotorOutput -= rightMotorOutput + 1.0;
+      rightMotorOutput = -1.0;
+    }
+  }
+
+  // Normalize the wheel speeds
+  double maxMagnitude =
+      std::max(std::abs(leftMotorOutput), std::abs(rightMotorOutput));
+  if (maxMagnitude > 1.0) {
+    leftMotorOutput /= maxMagnitude;
+    rightMotorOutput /= maxMagnitude;
+  }
+
+  m_leftMotor->Set(leftMotorOutput * m_maxOutput);
+  m_rightMotor->Set(rightMotorOutput * m_maxOutput *
+                    m_rightSideInvertMultiplier);
+
+  Feed();
+}
+
+void DifferentialDrive::TankDrive(double leftSpeed, double rightSpeed,
+                                  bool squareInputs) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
+               HALUsageReporting::kRobotDrive2_DifferentialTank, 2);
+    reported = true;
+  }
+
+  leftSpeed = std::clamp(leftSpeed, -1.0, 1.0);
+  leftSpeed = ApplyDeadband(leftSpeed, m_deadband);
+
+  rightSpeed = std::clamp(rightSpeed, -1.0, 1.0);
+  rightSpeed = ApplyDeadband(rightSpeed, m_deadband);
+
+  // Square the inputs (while preserving the sign) to increase fine control
+  // while permitting full power.
+  if (squareInputs) {
+    leftSpeed = std::copysign(leftSpeed * leftSpeed, leftSpeed);
+    rightSpeed = std::copysign(rightSpeed * rightSpeed, rightSpeed);
+  }
+
+  m_leftMotor->Set(leftSpeed * m_maxOutput);
+  m_rightMotor->Set(rightSpeed * m_maxOutput * m_rightSideInvertMultiplier);
+
+  Feed();
+}
+
+void DifferentialDrive::SetQuickStopThreshold(double threshold) {
+  m_quickStopThreshold = threshold;
+}
+
+void DifferentialDrive::SetQuickStopAlpha(double alpha) {
+  m_quickStopAlpha = alpha;
+}
+
+bool DifferentialDrive::IsRightSideInverted() const {
+  return m_rightSideInvertMultiplier == -1.0;
+}
+
+void DifferentialDrive::SetRightSideInverted(bool rightSideInverted) {
+  m_rightSideInvertMultiplier = rightSideInverted ? -1.0 : 1.0;
+}
+
+void DifferentialDrive::StopMotor() {
+  m_leftMotor->StopMotor();
+  m_rightMotor->StopMotor();
+  Feed();
+}
+
+void DifferentialDrive::GetDescription(wpi::raw_ostream& desc) const {
+  desc << "DifferentialDrive";
+}
+
+void DifferentialDrive::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("DifferentialDrive");
+  builder.SetActuator(true);
+  builder.SetSafeState([=] { StopMotor(); });
+  builder.AddDoubleProperty("Left Motor Speed",
+                            [=]() { return m_leftMotor->Get(); },
+                            [=](double value) { m_leftMotor->Set(value); });
+  builder.AddDoubleProperty(
+      "Right Motor Speed",
+      [=]() { return m_rightMotor->Get() * m_rightSideInvertMultiplier; },
+      [=](double value) {
+        m_rightMotor->Set(value * m_rightSideInvertMultiplier);
+      });
+}
diff --git a/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp b/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp
new file mode 100644
index 0000000..e03951b
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp
@@ -0,0 +1,119 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/drive/KilloughDrive.h"
+
+#include <algorithm>
+#include <cmath>
+
+#include <hal/FRCUsageReporting.h>
+#include <wpi/math>
+
+#include "frc/SpeedController.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+KilloughDrive::KilloughDrive(SpeedController& leftMotor,
+                             SpeedController& rightMotor,
+                             SpeedController& backMotor)
+    : KilloughDrive(leftMotor, rightMotor, backMotor, kDefaultLeftMotorAngle,
+                    kDefaultRightMotorAngle, kDefaultBackMotorAngle) {}
+
+KilloughDrive::KilloughDrive(SpeedController& leftMotor,
+                             SpeedController& rightMotor,
+                             SpeedController& backMotor, double leftMotorAngle,
+                             double rightMotorAngle, double backMotorAngle)
+    : m_leftMotor(&leftMotor),
+      m_rightMotor(&rightMotor),
+      m_backMotor(&backMotor) {
+  m_leftVec = {std::cos(leftMotorAngle * (wpi::math::pi / 180.0)),
+               std::sin(leftMotorAngle * (wpi::math::pi / 180.0))};
+  m_rightVec = {std::cos(rightMotorAngle * (wpi::math::pi / 180.0)),
+                std::sin(rightMotorAngle * (wpi::math::pi / 180.0))};
+  m_backVec = {std::cos(backMotorAngle * (wpi::math::pi / 180.0)),
+               std::sin(backMotorAngle * (wpi::math::pi / 180.0))};
+  auto& registry = SendableRegistry::GetInstance();
+  registry.AddChild(this, m_leftMotor);
+  registry.AddChild(this, m_rightMotor);
+  registry.AddChild(this, m_backMotor);
+  static int instances = 0;
+  ++instances;
+  registry.AddLW(this, "KilloughDrive", instances);
+}
+
+void KilloughDrive::DriveCartesian(double ySpeed, double xSpeed,
+                                   double zRotation, double gyroAngle) {
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
+               HALUsageReporting::kRobotDrive2_KilloughCartesian, 3);
+    reported = true;
+  }
+
+  ySpeed = std::clamp(ySpeed, -1.0, 1.0);
+  ySpeed = ApplyDeadband(ySpeed, m_deadband);
+
+  xSpeed = std::clamp(xSpeed, -1.0, 1.0);
+  xSpeed = ApplyDeadband(xSpeed, m_deadband);
+
+  // Compensate for gyro angle.
+  Vector2d input{ySpeed, xSpeed};
+  input.Rotate(-gyroAngle);
+
+  double wheelSpeeds[3];
+  wheelSpeeds[kLeft] = input.ScalarProject(m_leftVec) + zRotation;
+  wheelSpeeds[kRight] = input.ScalarProject(m_rightVec) + zRotation;
+  wheelSpeeds[kBack] = input.ScalarProject(m_backVec) + zRotation;
+
+  Normalize(wheelSpeeds);
+
+  m_leftMotor->Set(wheelSpeeds[kLeft] * m_maxOutput);
+  m_rightMotor->Set(wheelSpeeds[kRight] * m_maxOutput);
+  m_backMotor->Set(wheelSpeeds[kBack] * m_maxOutput);
+
+  Feed();
+}
+
+void KilloughDrive::DrivePolar(double magnitude, double angle,
+                               double zRotation) {
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
+               HALUsageReporting::kRobotDrive2_KilloughPolar, 3);
+    reported = true;
+  }
+
+  DriveCartesian(magnitude * std::sin(angle * (wpi::math::pi / 180.0)),
+                 magnitude * std::cos(angle * (wpi::math::pi / 180.0)),
+                 zRotation, 0.0);
+}
+
+void KilloughDrive::StopMotor() {
+  m_leftMotor->StopMotor();
+  m_rightMotor->StopMotor();
+  m_backMotor->StopMotor();
+  Feed();
+}
+
+void KilloughDrive::GetDescription(wpi::raw_ostream& desc) const {
+  desc << "KilloughDrive";
+}
+
+void KilloughDrive::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("KilloughDrive");
+  builder.SetActuator(true);
+  builder.SetSafeState([=] { StopMotor(); });
+  builder.AddDoubleProperty("Left Motor Speed",
+                            [=]() { return m_leftMotor->Get(); },
+                            [=](double value) { m_leftMotor->Set(value); });
+  builder.AddDoubleProperty("Right Motor Speed",
+                            [=]() { return m_rightMotor->Get(); },
+                            [=](double value) { m_rightMotor->Set(value); });
+  builder.AddDoubleProperty("Back Motor Speed",
+                            [=]() { return m_backMotor->Get(); },
+                            [=](double value) { m_backMotor->Set(value); });
+}
diff --git a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp
new file mode 100644
index 0000000..0102d6a
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp
@@ -0,0 +1,132 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/drive/MecanumDrive.h"
+
+#include <algorithm>
+#include <cmath>
+
+#include <hal/FRCUsageReporting.h>
+#include <wpi/math>
+
+#include "frc/SpeedController.h"
+#include "frc/drive/Vector2d.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+MecanumDrive::MecanumDrive(SpeedController& frontLeftMotor,
+                           SpeedController& rearLeftMotor,
+                           SpeedController& frontRightMotor,
+                           SpeedController& rearRightMotor)
+    : m_frontLeftMotor(&frontLeftMotor),
+      m_rearLeftMotor(&rearLeftMotor),
+      m_frontRightMotor(&frontRightMotor),
+      m_rearRightMotor(&rearRightMotor) {
+  auto& registry = SendableRegistry::GetInstance();
+  registry.AddChild(this, m_frontLeftMotor);
+  registry.AddChild(this, m_rearLeftMotor);
+  registry.AddChild(this, m_frontRightMotor);
+  registry.AddChild(this, m_rearRightMotor);
+  static int instances = 0;
+  ++instances;
+  registry.AddLW(this, "MecanumDrive", instances);
+}
+
+void MecanumDrive::DriveCartesian(double ySpeed, double xSpeed,
+                                  double zRotation, double gyroAngle) {
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
+               HALUsageReporting::kRobotDrive2_MecanumCartesian, 4);
+    reported = true;
+  }
+
+  ySpeed = std::clamp(ySpeed, -1.0, 1.0);
+  ySpeed = ApplyDeadband(ySpeed, m_deadband);
+
+  xSpeed = std::clamp(xSpeed, -1.0, 1.0);
+  xSpeed = ApplyDeadband(xSpeed, m_deadband);
+
+  // Compensate for gyro angle.
+  Vector2d input{ySpeed, xSpeed};
+  input.Rotate(-gyroAngle);
+
+  double wheelSpeeds[4];
+  wheelSpeeds[kFrontLeft] = input.x + input.y + zRotation;
+  wheelSpeeds[kFrontRight] = -input.x + input.y - zRotation;
+  wheelSpeeds[kRearLeft] = -input.x + input.y + zRotation;
+  wheelSpeeds[kRearRight] = input.x + input.y - zRotation;
+
+  Normalize(wheelSpeeds);
+
+  m_frontLeftMotor->Set(wheelSpeeds[kFrontLeft] * m_maxOutput);
+  m_frontRightMotor->Set(wheelSpeeds[kFrontRight] * m_maxOutput *
+                         m_rightSideInvertMultiplier);
+  m_rearLeftMotor->Set(wheelSpeeds[kRearLeft] * m_maxOutput);
+  m_rearRightMotor->Set(wheelSpeeds[kRearRight] * m_maxOutput *
+                        m_rightSideInvertMultiplier);
+
+  Feed();
+}
+
+void MecanumDrive::DrivePolar(double magnitude, double angle,
+                              double zRotation) {
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive,
+               HALUsageReporting::kRobotDrive2_MecanumPolar, 4);
+    reported = true;
+  }
+
+  DriveCartesian(magnitude * std::sin(angle * (wpi::math::pi / 180.0)),
+                 magnitude * std::cos(angle * (wpi::math::pi / 180.0)),
+                 zRotation, 0.0);
+}
+
+bool MecanumDrive::IsRightSideInverted() const {
+  return m_rightSideInvertMultiplier == -1.0;
+}
+
+void MecanumDrive::SetRightSideInverted(bool rightSideInverted) {
+  m_rightSideInvertMultiplier = rightSideInverted ? -1.0 : 1.0;
+}
+
+void MecanumDrive::StopMotor() {
+  m_frontLeftMotor->StopMotor();
+  m_frontRightMotor->StopMotor();
+  m_rearLeftMotor->StopMotor();
+  m_rearRightMotor->StopMotor();
+  Feed();
+}
+
+void MecanumDrive::GetDescription(wpi::raw_ostream& desc) const {
+  desc << "MecanumDrive";
+}
+
+void MecanumDrive::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("MecanumDrive");
+  builder.SetActuator(true);
+  builder.SetSafeState([=] { StopMotor(); });
+  builder.AddDoubleProperty(
+      "Front Left Motor Speed", [=]() { return m_frontLeftMotor->Get(); },
+      [=](double value) { m_frontLeftMotor->Set(value); });
+  builder.AddDoubleProperty(
+      "Front Right Motor Speed",
+      [=]() { return m_frontRightMotor->Get() * m_rightSideInvertMultiplier; },
+      [=](double value) {
+        m_frontRightMotor->Set(value * m_rightSideInvertMultiplier);
+      });
+  builder.AddDoubleProperty("Rear Left Motor Speed",
+                            [=]() { return m_rearLeftMotor->Get(); },
+                            [=](double value) { m_rearLeftMotor->Set(value); });
+  builder.AddDoubleProperty(
+      "Rear Right Motor Speed",
+      [=]() { return m_rearRightMotor->Get() * m_rightSideInvertMultiplier; },
+      [=](double value) {
+        m_rearRightMotor->Set(value * m_rightSideInvertMultiplier);
+      });
+}
diff --git a/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp b/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp
new file mode 100644
index 0000000..fbce5a1
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/drive/RobotDriveBase.h"
+
+#include <algorithm>
+#include <cmath>
+#include <cstddef>
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/Base.h"
+#include "frc/SpeedController.h"
+
+using namespace frc;
+
+RobotDriveBase::RobotDriveBase() { SetSafetyEnabled(true); }
+
+void RobotDriveBase::SetDeadband(double deadband) { m_deadband = deadband; }
+
+void RobotDriveBase::SetMaxOutput(double maxOutput) { m_maxOutput = maxOutput; }
+
+void RobotDriveBase::FeedWatchdog() { Feed(); }
+
+double RobotDriveBase::ApplyDeadband(double value, double deadband) {
+  if (std::abs(value) > deadband) {
+    if (value > 0.0) {
+      return (value - deadband) / (1.0 - deadband);
+    } else {
+      return (value + deadband) / (1.0 - deadband);
+    }
+  } else {
+    return 0.0;
+  }
+}
+
+void RobotDriveBase::Normalize(wpi::MutableArrayRef<double> wheelSpeeds) {
+  double maxMagnitude = std::abs(wheelSpeeds[0]);
+  for (size_t i = 1; i < wheelSpeeds.size(); i++) {
+    double temp = std::abs(wheelSpeeds[i]);
+    if (maxMagnitude < temp) {
+      maxMagnitude = temp;
+    }
+  }
+  if (maxMagnitude > 1.0) {
+    for (size_t i = 0; i < wheelSpeeds.size(); i++) {
+      wheelSpeeds[i] = wheelSpeeds[i] / maxMagnitude;
+    }
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/drive/Vector2d.cpp b/wpilibc/src/main/native/cpp/drive/Vector2d.cpp
new file mode 100644
index 0000000..a6e68a6
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/drive/Vector2d.cpp
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/drive/Vector2d.h"
+
+#include <cmath>
+
+#include <wpi/math>
+
+using namespace frc;
+
+Vector2d::Vector2d(double x, double y) {
+  this->x = x;
+  this->y = y;
+}
+
+void Vector2d::Rotate(double angle) {
+  double cosA = std::cos(angle * (wpi::math::pi / 180.0));
+  double sinA = std::sin(angle * (wpi::math::pi / 180.0));
+  double out[2];
+  out[0] = x * cosA - y * sinA;
+  out[1] = x * sinA + y * cosA;
+  x = out[0];
+  y = out[1];
+}
+
+double Vector2d::Dot(const Vector2d& vec) const {
+  return x * vec.x + y * vec.y;
+}
+
+double Vector2d::Magnitude() const { return std::sqrt(x * x + y * y); }
+
+double Vector2d::ScalarProject(const Vector2d& vec) const {
+  return Dot(vec) / vec.Magnitude();
+}
diff --git a/wpilibc/src/main/native/cpp/filters/Filter.cpp b/wpilibc/src/main/native/cpp/filters/Filter.cpp
new file mode 100644
index 0000000..c25d7af
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/filters/Filter.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/filters/Filter.h"
+
+#include "frc/Base.h"
+
+using namespace frc;
+
+Filter::Filter(PIDSource& source)
+    : m_source(std::shared_ptr<PIDSource>(&source, NullDeleter<PIDSource>())) {}
+
+Filter::Filter(std::shared_ptr<PIDSource> source)
+    : m_source(std::move(source)) {}
+
+void Filter::SetPIDSourceType(PIDSourceType pidSource) {
+  m_source->SetPIDSourceType(pidSource);
+}
+
+PIDSourceType Filter::GetPIDSourceType() const {
+  return m_source->GetPIDSourceType();
+}
+
+double Filter::PIDGetSource() { return m_source->PIDGet(); }
diff --git a/wpilibc/src/main/native/cpp/filters/LinearDigitalFilter.cpp b/wpilibc/src/main/native/cpp/filters/LinearDigitalFilter.cpp
new file mode 100644
index 0000000..434cc27
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/filters/LinearDigitalFilter.cpp
@@ -0,0 +1,136 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/filters/LinearDigitalFilter.h"
+
+#include <cassert>
+#include <cmath>
+
+#include <hal/FRCUsageReporting.h>
+
+using namespace frc;
+
+LinearDigitalFilter::LinearDigitalFilter(PIDSource& source,
+                                         wpi::ArrayRef<double> ffGains,
+                                         wpi::ArrayRef<double> fbGains)
+    : Filter(source),
+      m_inputs(ffGains.size()),
+      m_outputs(fbGains.size()),
+      m_inputGains(ffGains),
+      m_outputGains(fbGains) {
+  static int instances = 0;
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_LinearFilter, instances);
+}
+
+LinearDigitalFilter::LinearDigitalFilter(PIDSource& source,
+                                         std::initializer_list<double> ffGains,
+                                         std::initializer_list<double> fbGains)
+    : LinearDigitalFilter(source,
+                          wpi::makeArrayRef(ffGains.begin(), ffGains.end()),
+                          wpi::makeArrayRef(fbGains.begin(), fbGains.end())) {}
+
+LinearDigitalFilter::LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                                         wpi::ArrayRef<double> ffGains,
+                                         wpi::ArrayRef<double> fbGains)
+    : Filter(source),
+      m_inputs(ffGains.size()),
+      m_outputs(fbGains.size()),
+      m_inputGains(ffGains),
+      m_outputGains(fbGains) {
+  static int instances = 0;
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_LinearFilter, instances);
+}
+
+LinearDigitalFilter::LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                                         std::initializer_list<double> ffGains,
+                                         std::initializer_list<double> fbGains)
+    : LinearDigitalFilter(source,
+                          wpi::makeArrayRef(ffGains.begin(), ffGains.end()),
+                          wpi::makeArrayRef(fbGains.begin(), fbGains.end())) {}
+
+LinearDigitalFilter LinearDigitalFilter::SinglePoleIIR(PIDSource& source,
+                                                       double timeConstant,
+                                                       double period) {
+  double gain = std::exp(-period / timeConstant);
+  return LinearDigitalFilter(source, {1.0 - gain}, {-gain});
+}
+
+LinearDigitalFilter LinearDigitalFilter::HighPass(PIDSource& source,
+                                                  double timeConstant,
+                                                  double period) {
+  double gain = std::exp(-period / timeConstant);
+  return LinearDigitalFilter(source, {gain, -gain}, {-gain});
+}
+
+LinearDigitalFilter LinearDigitalFilter::MovingAverage(PIDSource& source,
+                                                       int taps) {
+  assert(taps > 0);
+
+  std::vector<double> gains(taps, 1.0 / taps);
+  return LinearDigitalFilter(source, gains, {});
+}
+
+LinearDigitalFilter LinearDigitalFilter::SinglePoleIIR(
+    std::shared_ptr<PIDSource> source, double timeConstant, double period) {
+  double gain = std::exp(-period / timeConstant);
+  return LinearDigitalFilter(std::move(source), {1.0 - gain}, {-gain});
+}
+
+LinearDigitalFilter LinearDigitalFilter::HighPass(
+    std::shared_ptr<PIDSource> source, double timeConstant, double period) {
+  double gain = std::exp(-period / timeConstant);
+  return LinearDigitalFilter(std::move(source), {gain, -gain}, {-gain});
+}
+
+LinearDigitalFilter LinearDigitalFilter::MovingAverage(
+    std::shared_ptr<PIDSource> source, int taps) {
+  assert(taps > 0);
+
+  std::vector<double> gains(taps, 1.0 / taps);
+  return LinearDigitalFilter(std::move(source), gains, {});
+}
+
+double LinearDigitalFilter::Get() const {
+  double retVal = 0.0;
+
+  // Calculate the new value
+  for (size_t i = 0; i < m_inputGains.size(); i++) {
+    retVal += m_inputs[i] * m_inputGains[i];
+  }
+  for (size_t i = 0; i < m_outputGains.size(); i++) {
+    retVal -= m_outputs[i] * m_outputGains[i];
+  }
+
+  return retVal;
+}
+
+void LinearDigitalFilter::Reset() {
+  m_inputs.reset();
+  m_outputs.reset();
+}
+
+double LinearDigitalFilter::PIDGet() {
+  double retVal = 0.0;
+
+  // Rotate the inputs
+  m_inputs.push_front(PIDGetSource());
+
+  // Calculate the new value
+  for (size_t i = 0; i < m_inputGains.size(); i++) {
+    retVal += m_inputs[i] * m_inputGains[i];
+  }
+  for (size_t i = 0; i < m_outputGains.size(); i++) {
+    retVal -= m_outputs[i] * m_outputGains[i];
+  }
+
+  // Rotate the outputs
+  m_outputs.push_front(retVal);
+
+  return retVal;
+}
diff --git a/wpilibc/src/main/native/cpp/frc2/Timer.cpp b/wpilibc/src/main/native/cpp/frc2/Timer.cpp
new file mode 100644
index 0000000..76721bc
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/frc2/Timer.cpp
@@ -0,0 +1,137 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc2/Timer.h"
+
+#include <chrono>
+#include <thread>
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/DriverStation.h"
+#include "frc/RobotController.h"
+
+namespace frc2 {
+
+void Wait(units::second_t seconds) {
+  std::this_thread::sleep_for(
+      std::chrono::duration<double>(seconds.to<double>()));
+}
+
+units::second_t GetTime() {
+  using std::chrono::duration;
+  using std::chrono::duration_cast;
+  using std::chrono::system_clock;
+
+  return units::second_t(
+      duration_cast<duration<double>>(system_clock::now().time_since_epoch())
+          .count());
+}
+
+}  // namespace frc2
+
+using namespace frc2;
+
+// for compatibility with msvc12--see C2864
+const units::second_t Timer::kRolloverTime = units::second_t((1ll << 32) / 1e6);
+
+Timer::Timer() { Reset(); }
+
+Timer::Timer(const Timer& rhs)
+    : m_startTime(rhs.m_startTime),
+      m_accumulatedTime(rhs.m_accumulatedTime),
+      m_running(rhs.m_running) {}
+
+Timer& Timer::operator=(const Timer& rhs) {
+  std::scoped_lock lock(m_mutex, rhs.m_mutex);
+
+  m_startTime = rhs.m_startTime;
+  m_accumulatedTime = rhs.m_accumulatedTime;
+  m_running = rhs.m_running;
+
+  return *this;
+}
+
+Timer::Timer(Timer&& rhs)
+    : m_startTime(std::move(rhs.m_startTime)),
+      m_accumulatedTime(std::move(rhs.m_accumulatedTime)),
+      m_running(std::move(rhs.m_running)) {}
+
+Timer& Timer::operator=(Timer&& rhs) {
+  std::scoped_lock lock(m_mutex, rhs.m_mutex);
+
+  m_startTime = std::move(rhs.m_startTime);
+  m_accumulatedTime = std::move(rhs.m_accumulatedTime);
+  m_running = std::move(rhs.m_running);
+
+  return *this;
+}
+
+units::second_t Timer::Get() const {
+  units::second_t result;
+  units::second_t currentTime = GetFPGATimestamp();
+
+  std::scoped_lock lock(m_mutex);
+  if (m_running) {
+    // If the current time is before the start time, then the FPGA clock rolled
+    // over. Compensate by adding the ~71 minutes that it takes to roll over to
+    // the current time.
+    if (currentTime < m_startTime) {
+      currentTime += kRolloverTime;
+    }
+
+    result = (currentTime - m_startTime) + m_accumulatedTime;
+  } else {
+    result = m_accumulatedTime;
+  }
+
+  return result;
+}
+
+void Timer::Reset() {
+  std::scoped_lock lock(m_mutex);
+  m_accumulatedTime = 0_s;
+  m_startTime = GetFPGATimestamp();
+}
+
+void Timer::Start() {
+  std::scoped_lock lock(m_mutex);
+  if (!m_running) {
+    m_startTime = GetFPGATimestamp();
+    m_running = true;
+  }
+}
+
+void Timer::Stop() {
+  units::second_t temp = Get();
+
+  std::scoped_lock lock(m_mutex);
+  if (m_running) {
+    m_accumulatedTime = temp;
+    m_running = false;
+  }
+}
+
+bool Timer::HasPeriodPassed(units::second_t period) {
+  if (Get() > period) {
+    std::scoped_lock lock(m_mutex);
+    // Advance the start time by the period.
+    m_startTime += period;
+    // Don't set it to the current time... we want to avoid drift.
+    return true;
+  }
+  return false;
+}
+
+units::second_t Timer::GetFPGATimestamp() {
+  // FPGA returns the timestamp in microseconds
+  return units::second_t(frc::RobotController::GetFPGATime() * 1.0e-6);
+}
+
+units::second_t Timer::GetMatchTime() {
+  return units::second_t(frc::DriverStation::GetInstance().GetMatchTime());
+}
diff --git a/wpilibc/src/main/native/cpp/geometry/Pose2d.cpp b/wpilibc/src/main/native/cpp/geometry/Pose2d.cpp
new file mode 100644
index 0000000..1754830
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/geometry/Pose2d.cpp
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/geometry/Pose2d.h"
+
+#include <cmath>
+
+#include <wpi/json.h>
+
+using namespace frc;
+
+Pose2d::Pose2d(Translation2d translation, Rotation2d rotation)
+    : m_translation(translation), m_rotation(rotation) {}
+
+Pose2d::Pose2d(units::meter_t x, units::meter_t y, Rotation2d rotation)
+    : m_translation(x, y), m_rotation(rotation) {}
+
+Pose2d Pose2d::operator+(const Transform2d& other) const {
+  return TransformBy(other);
+}
+
+Pose2d& Pose2d::operator+=(const Transform2d& other) {
+  m_translation += other.Translation().RotateBy(m_rotation);
+  m_rotation += other.Rotation();
+  return *this;
+}
+
+Transform2d Pose2d::operator-(const Pose2d& other) const {
+  const auto pose = this->RelativeTo(other);
+  return Transform2d(pose.Translation(), pose.Rotation());
+}
+
+bool Pose2d::operator==(const Pose2d& other) const {
+  return m_translation == other.m_translation && m_rotation == other.m_rotation;
+}
+
+bool Pose2d::operator!=(const Pose2d& other) const {
+  return !operator==(other);
+}
+
+Pose2d Pose2d::TransformBy(const Transform2d& other) const {
+  return {m_translation + (other.Translation().RotateBy(m_rotation)),
+          m_rotation + other.Rotation()};
+}
+
+Pose2d Pose2d::RelativeTo(const Pose2d& other) const {
+  const Transform2d transform{other, *this};
+  return {transform.Translation(), transform.Rotation()};
+}
+
+Pose2d Pose2d::Exp(const Twist2d& twist) const {
+  const auto dx = twist.dx;
+  const auto dy = twist.dy;
+  const auto dtheta = twist.dtheta.to<double>();
+
+  const auto sinTheta = std::sin(dtheta);
+  const auto cosTheta = std::cos(dtheta);
+
+  double s, c;
+  if (std::abs(dtheta) < 1E-9) {
+    s = 1.0 - 1.0 / 6.0 * dtheta * dtheta;
+    c = 0.5 * dtheta;
+  } else {
+    s = sinTheta / dtheta;
+    c = (1 - cosTheta) / dtheta;
+  }
+
+  const Transform2d transform{Translation2d{dx * s - dy * c, dx * c + dy * s},
+                              Rotation2d{cosTheta, sinTheta}};
+
+  return *this + transform;
+}
+
+Twist2d Pose2d::Log(const Pose2d& end) const {
+  const auto transform = end.RelativeTo(*this);
+  const auto dtheta = transform.Rotation().Radians().to<double>();
+  const auto halfDtheta = dtheta / 2.0;
+
+  const auto cosMinusOne = transform.Rotation().Cos() - 1;
+
+  double halfThetaByTanOfHalfDtheta;
+
+  if (std::abs(cosMinusOne) < 1E-9) {
+    halfThetaByTanOfHalfDtheta = 1.0 - 1.0 / 12.0 * dtheta * dtheta;
+  } else {
+    halfThetaByTanOfHalfDtheta =
+        -(halfDtheta * transform.Rotation().Sin()) / cosMinusOne;
+  }
+
+  const Translation2d translationPart =
+      transform.Translation().RotateBy(
+          {halfThetaByTanOfHalfDtheta, -halfDtheta}) *
+      std::hypot(halfThetaByTanOfHalfDtheta, halfDtheta);
+
+  return {translationPart.X(), translationPart.Y(), units::radian_t(dtheta)};
+}
+
+void frc::to_json(wpi::json& json, const Pose2d& pose) {
+  json = wpi::json{{"translation", pose.Translation()},
+                   {"rotation", pose.Rotation()}};
+}
+
+void frc::from_json(const wpi::json& json, Pose2d& pose) {
+  pose = Pose2d{json.at("translation").get<Translation2d>(),
+                json.at("rotation").get<Rotation2d>()};
+}
diff --git a/wpilibc/src/main/native/cpp/geometry/Rotation2d.cpp b/wpilibc/src/main/native/cpp/geometry/Rotation2d.cpp
new file mode 100644
index 0000000..a3c4bea
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/geometry/Rotation2d.cpp
@@ -0,0 +1,80 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/geometry/Rotation2d.h"
+
+#include <cmath>
+
+#include <wpi/json.h>
+
+using namespace frc;
+
+Rotation2d::Rotation2d(units::radian_t value)
+    : m_value(value),
+      m_cos(units::math::cos(value)),
+      m_sin(units::math::sin(value)) {}
+
+Rotation2d::Rotation2d(double x, double y) {
+  const auto magnitude = std::hypot(x, y);
+  if (magnitude > 1e-6) {
+    m_sin = y / magnitude;
+    m_cos = x / magnitude;
+  } else {
+    m_sin = 0.0;
+    m_cos = 1.0;
+  }
+  m_value = units::radian_t(std::atan2(m_sin, m_cos));
+}
+
+Rotation2d Rotation2d::operator+(const Rotation2d& other) const {
+  return RotateBy(other);
+}
+
+Rotation2d& Rotation2d::operator+=(const Rotation2d& other) {
+  double cos = Cos() * other.Cos() - Sin() * other.Sin();
+  double sin = Cos() * other.Sin() + Sin() * other.Cos();
+  m_cos = cos;
+  m_sin = sin;
+  m_value = units::radian_t(std::atan2(m_sin, m_cos));
+  return *this;
+}
+
+Rotation2d Rotation2d::operator-(const Rotation2d& other) const {
+  return *this + -other;
+}
+
+Rotation2d& Rotation2d::operator-=(const Rotation2d& other) {
+  *this += -other;
+  return *this;
+}
+
+Rotation2d Rotation2d::operator-() const { return Rotation2d(-m_value); }
+
+Rotation2d Rotation2d::operator*(double scalar) const {
+  return Rotation2d(m_value * scalar);
+}
+
+bool Rotation2d::operator==(const Rotation2d& other) const {
+  return units::math::abs(m_value - other.m_value) < 1E-9_rad;
+}
+
+bool Rotation2d::operator!=(const Rotation2d& other) const {
+  return !operator==(other);
+}
+
+Rotation2d Rotation2d::RotateBy(const Rotation2d& other) const {
+  return {Cos() * other.Cos() - Sin() * other.Sin(),
+          Cos() * other.Sin() + Sin() * other.Cos()};
+}
+
+void frc::to_json(wpi::json& json, const Rotation2d& rotation) {
+  json = wpi::json{{"radians", rotation.Radians().to<double>()}};
+}
+
+void frc::from_json(const wpi::json& json, Rotation2d& rotation) {
+  rotation = Rotation2d{units::radian_t{json.at("radians").get<double>()}};
+}
diff --git a/wpilibc/src/main/native/cpp/geometry/Transform2d.cpp b/wpilibc/src/main/native/cpp/geometry/Transform2d.cpp
new file mode 100644
index 0000000..04f0419
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/geometry/Transform2d.cpp
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/geometry/Transform2d.h"
+
+#include "frc/geometry/Pose2d.h"
+
+using namespace frc;
+
+Transform2d::Transform2d(Pose2d initial, Pose2d final) {
+  // We are rotating the difference between the translations
+  // using a clockwise rotation matrix. This transforms the global
+  // delta into a local delta (relative to the initial pose).
+  m_translation = (final.Translation() - initial.Translation())
+                      .RotateBy(-initial.Rotation());
+
+  m_rotation = final.Rotation() - initial.Rotation();
+}
+
+Transform2d::Transform2d(Translation2d translation, Rotation2d rotation)
+    : m_translation(translation), m_rotation(rotation) {}
+
+bool Transform2d::operator==(const Transform2d& other) const {
+  return m_translation == other.m_translation && m_rotation == other.m_rotation;
+}
+
+bool Transform2d::operator!=(const Transform2d& other) const {
+  return !operator==(other);
+}
diff --git a/wpilibc/src/main/native/cpp/geometry/Translation2d.cpp b/wpilibc/src/main/native/cpp/geometry/Translation2d.cpp
new file mode 100644
index 0000000..c3db7e3
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/geometry/Translation2d.cpp
@@ -0,0 +1,87 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/geometry/Translation2d.h"
+
+#include <wpi/json.h>
+
+using namespace frc;
+
+Translation2d::Translation2d(units::meter_t x, units::meter_t y)
+    : m_x(x), m_y(y) {}
+
+units::meter_t Translation2d::Distance(const Translation2d& other) const {
+  return units::math::hypot(other.m_x - m_x, other.m_y - m_y);
+}
+
+units::meter_t Translation2d::Norm() const {
+  return units::math::hypot(m_x, m_y);
+}
+
+Translation2d Translation2d::RotateBy(const Rotation2d& other) const {
+  return {m_x * other.Cos() - m_y * other.Sin(),
+          m_x * other.Sin() + m_y * other.Cos()};
+}
+
+Translation2d Translation2d::operator+(const Translation2d& other) const {
+  return {X() + other.X(), Y() + other.Y()};
+}
+
+Translation2d& Translation2d::operator+=(const Translation2d& other) {
+  m_x += other.m_x;
+  m_y += other.m_y;
+  return *this;
+}
+
+Translation2d Translation2d::operator-(const Translation2d& other) const {
+  return *this + -other;
+}
+
+Translation2d& Translation2d::operator-=(const Translation2d& other) {
+  *this += -other;
+  return *this;
+}
+
+Translation2d Translation2d::operator-() const { return {-m_x, -m_y}; }
+
+Translation2d Translation2d::operator*(double scalar) const {
+  return {scalar * m_x, scalar * m_y};
+}
+
+Translation2d& Translation2d::operator*=(double scalar) {
+  m_x *= scalar;
+  m_y *= scalar;
+  return *this;
+}
+
+Translation2d Translation2d::operator/(double scalar) const {
+  return *this * (1.0 / scalar);
+}
+
+bool Translation2d::operator==(const Translation2d& other) const {
+  return units::math::abs(m_x - other.m_x) < 1E-9_m &&
+         units::math::abs(m_y - other.m_y) < 1E-9_m;
+}
+
+bool Translation2d::operator!=(const Translation2d& other) const {
+  return !operator==(other);
+}
+
+Translation2d& Translation2d::operator/=(double scalar) {
+  *this *= (1.0 / scalar);
+  return *this;
+}
+
+void frc::to_json(wpi::json& json, const Translation2d& translation) {
+  json = wpi::json{{"x", translation.X().to<double>()},
+                   {"y", translation.Y().to<double>()}};
+}
+
+void frc::from_json(const wpi::json& json, Translation2d& translation) {
+  translation = Translation2d{units::meter_t{json.at("x").get<double>()},
+                              units::meter_t{json.at("y").get<double>()}};
+}
diff --git a/wpilibc/src/main/native/cpp/interfaces/Potentiometer.cpp b/wpilibc/src/main/native/cpp/interfaces/Potentiometer.cpp
new file mode 100644
index 0000000..44f4aab
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/interfaces/Potentiometer.cpp
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/interfaces/Potentiometer.h"
+
+#include "frc/Utility.h"
+
+using namespace frc;
+
+void Potentiometer::SetPIDSourceType(PIDSourceType pidSource) {
+  if (wpi_assert(pidSource == PIDSourceType::kDisplacement)) {
+    m_pidSource = pidSource;
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp b/wpilibc/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp
new file mode 100644
index 0000000..07a8e3b
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/kinematics/DifferentialDriveOdometry.h"
+
+#include <hal/FRCUsageReporting.h>
+
+using namespace frc;
+
+DifferentialDriveOdometry::DifferentialDriveOdometry(
+    const Rotation2d& gyroAngle, const Pose2d& initialPose)
+    : m_pose(initialPose) {
+  m_previousAngle = m_pose.Rotation();
+  m_gyroOffset = m_pose.Rotation() - gyroAngle;
+  HAL_Report(HALUsageReporting::kResourceType_Odometry,
+             HALUsageReporting::kOdometry_DifferentialDrive);
+}
+
+const Pose2d& DifferentialDriveOdometry::Update(const Rotation2d& gyroAngle,
+                                                units::meter_t leftDistance,
+                                                units::meter_t rightDistance) {
+  auto deltaLeftDistance = leftDistance - m_prevLeftDistance;
+  auto deltaRightDistance = rightDistance - m_prevRightDistance;
+
+  m_prevLeftDistance = leftDistance;
+  m_prevRightDistance = rightDistance;
+
+  auto averageDeltaDistance = (deltaLeftDistance + deltaRightDistance) / 2.0;
+  auto angle = gyroAngle + m_gyroOffset;
+
+  auto newPose = m_pose.Exp(
+      {averageDeltaDistance, 0_m, (angle - m_previousAngle).Radians()});
+
+  m_previousAngle = angle;
+  m_pose = {newPose.Translation(), angle};
+
+  return m_pose;
+}
diff --git a/wpilibc/src/main/native/cpp/kinematics/DifferentialDriveWheelSpeeds.cpp b/wpilibc/src/main/native/cpp/kinematics/DifferentialDriveWheelSpeeds.cpp
new file mode 100644
index 0000000..5b13f0e
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/kinematics/DifferentialDriveWheelSpeeds.cpp
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/kinematics/DifferentialDriveWheelSpeeds.h"
+
+using namespace frc;
+
+void DifferentialDriveWheelSpeeds::Normalize(
+    units::meters_per_second_t attainableMaxSpeed) {
+  auto realMaxSpeed =
+      units::math::max(units::math::abs(left), units::math::abs(right));
+
+  if (realMaxSpeed > attainableMaxSpeed) {
+    left = left / realMaxSpeed * attainableMaxSpeed;
+    right = right / realMaxSpeed * attainableMaxSpeed;
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/kinematics/MecanumDriveKinematics.cpp b/wpilibc/src/main/native/cpp/kinematics/MecanumDriveKinematics.cpp
new file mode 100644
index 0000000..cf6ebb5
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/kinematics/MecanumDriveKinematics.cpp
@@ -0,0 +1,68 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/kinematics/MecanumDriveKinematics.h"
+
+using namespace frc;
+
+MecanumDriveWheelSpeeds MecanumDriveKinematics::ToWheelSpeeds(
+    const ChassisSpeeds& chassisSpeeds, const Translation2d& centerOfRotation) {
+  // We have a new center of rotation. We need to compute the matrix again.
+  if (centerOfRotation != m_previousCoR) {
+    auto fl = m_frontLeftWheel - centerOfRotation;
+    auto fr = m_frontRightWheel - centerOfRotation;
+    auto rl = m_rearLeftWheel - centerOfRotation;
+    auto rr = m_rearRightWheel - centerOfRotation;
+
+    SetInverseKinematics(fl, fr, rl, rr);
+
+    m_previousCoR = centerOfRotation;
+  }
+
+  Eigen::Vector3d chassisSpeedsVector;
+  chassisSpeedsVector << chassisSpeeds.vx.to<double>(),
+      chassisSpeeds.vy.to<double>(), chassisSpeeds.omega.to<double>();
+
+  Eigen::Matrix<double, 4, 1> wheelsMatrix =
+      m_inverseKinematics * chassisSpeedsVector;
+
+  MecanumDriveWheelSpeeds wheelSpeeds;
+  wheelSpeeds.frontLeft = units::meters_per_second_t{wheelsMatrix(0, 0)};
+  wheelSpeeds.frontRight = units::meters_per_second_t{wheelsMatrix(1, 0)};
+  wheelSpeeds.rearLeft = units::meters_per_second_t{wheelsMatrix(2, 0)};
+  wheelSpeeds.rearRight = units::meters_per_second_t{wheelsMatrix(3, 0)};
+  return wheelSpeeds;
+}
+
+ChassisSpeeds MecanumDriveKinematics::ToChassisSpeeds(
+    const MecanumDriveWheelSpeeds& wheelSpeeds) {
+  Eigen::Matrix<double, 4, 1> wheelSpeedsMatrix;
+  // clang-format off
+  wheelSpeedsMatrix << wheelSpeeds.frontLeft.to<double>(), wheelSpeeds.frontRight.to<double>(),
+                       wheelSpeeds.rearLeft.to<double>(), wheelSpeeds.rearRight.to<double>();
+  // clang-format on
+
+  Eigen::Vector3d chassisSpeedsVector =
+      m_forwardKinematics.solve(wheelSpeedsMatrix);
+
+  return {units::meters_per_second_t{chassisSpeedsVector(0)},
+          units::meters_per_second_t{chassisSpeedsVector(1)},
+          units::radians_per_second_t{chassisSpeedsVector(2)}};
+}
+
+void MecanumDriveKinematics::SetInverseKinematics(Translation2d fl,
+                                                  Translation2d fr,
+                                                  Translation2d rl,
+                                                  Translation2d rr) {
+  // clang-format off
+  m_inverseKinematics << 1, -1, (-(fl.X() + fl.Y())).template to<double>(),
+                         1,  1, (fr.X() - fr.Y()).template to<double>(),
+                         1,  1, (rl.X() - rl.Y()).template to<double>(),
+                         1, -1, (-(rr.X() + rr.Y())).template to<double>();
+  // clang-format on
+  m_inverseKinematics /= std::sqrt(2);
+}
diff --git a/wpilibc/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp b/wpilibc/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp
new file mode 100644
index 0000000..3843483
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/kinematics/MecanumDriveOdometry.h"
+
+#include <hal/FRCUsageReporting.h>
+
+using namespace frc;
+
+MecanumDriveOdometry::MecanumDriveOdometry(MecanumDriveKinematics kinematics,
+                                           const Rotation2d& gyroAngle,
+                                           const Pose2d& initialPose)
+    : m_kinematics(kinematics), m_pose(initialPose) {
+  m_previousAngle = m_pose.Rotation();
+  m_gyroOffset = m_pose.Rotation() - gyroAngle;
+  HAL_Report(HALUsageReporting::kResourceType_Odometry,
+             HALUsageReporting::kOdometry_MecanumDrive);
+}
+
+const Pose2d& MecanumDriveOdometry::UpdateWithTime(
+    units::second_t currentTime, const Rotation2d& gyroAngle,
+    MecanumDriveWheelSpeeds wheelSpeeds) {
+  units::second_t deltaTime =
+      (m_previousTime >= 0_s) ? currentTime - m_previousTime : 0_s;
+  m_previousTime = currentTime;
+
+  auto angle = gyroAngle + m_gyroOffset;
+
+  auto [dx, dy, dtheta] = m_kinematics.ToChassisSpeeds(wheelSpeeds);
+  static_cast<void>(dtheta);
+
+  auto newPose = m_pose.Exp(
+      {dx * deltaTime, dy * deltaTime, (angle - m_previousAngle).Radians()});
+
+  m_previousAngle = angle;
+  m_pose = {newPose.Translation(), angle};
+
+  return m_pose;
+}
diff --git a/wpilibc/src/main/native/cpp/kinematics/MecanumDriveWheelSpeeds.cpp b/wpilibc/src/main/native/cpp/kinematics/MecanumDriveWheelSpeeds.cpp
new file mode 100644
index 0000000..1641ba8
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/kinematics/MecanumDriveWheelSpeeds.cpp
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/kinematics/MecanumDriveWheelSpeeds.h"
+
+#include <algorithm>
+#include <array>
+#include <cmath>
+
+using namespace frc;
+
+void MecanumDriveWheelSpeeds::Normalize(
+    units::meters_per_second_t attainableMaxSpeed) {
+  std::array<units::meters_per_second_t, 4> wheelSpeeds{frontLeft, frontRight,
+                                                        rearLeft, rearRight};
+  units::meters_per_second_t realMaxSpeed = *std::max_element(
+      wheelSpeeds.begin(), wheelSpeeds.end(), [](const auto& a, const auto& b) {
+        return units::math::abs(a) < units::math::abs(b);
+      });
+
+  if (realMaxSpeed > attainableMaxSpeed) {
+    for (int i = 0; i < 4; ++i) {
+      wheelSpeeds[i] = wheelSpeeds[i] / realMaxSpeed * attainableMaxSpeed;
+    }
+    frontLeft = wheelSpeeds[0];
+    frontRight = wheelSpeeds[1];
+    rearLeft = wheelSpeeds[2];
+    rearRight = wheelSpeeds[3];
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp b/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp
new file mode 100644
index 0000000..10996e4
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp
@@ -0,0 +1,161 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2012-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/livewindow/LiveWindow.h"
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/mutex.h>
+
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableBuilderImpl.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+using wpi::Twine;
+
+struct LiveWindow::Impl {
+  Impl();
+
+  struct Component {
+    bool firstTime = true;
+    bool telemetryEnabled = true;
+  };
+
+  wpi::mutex mutex;
+
+  SendableRegistry& registry;
+  int dataHandle;
+
+  std::shared_ptr<nt::NetworkTable> liveWindowTable;
+  std::shared_ptr<nt::NetworkTable> statusTable;
+  nt::NetworkTableEntry enabledEntry;
+
+  bool startLiveWindow = false;
+  bool liveWindowEnabled = false;
+  bool telemetryEnabled = true;
+
+  std::shared_ptr<Component> GetOrAdd(Sendable* sendable);
+};
+
+LiveWindow::Impl::Impl()
+    : registry(SendableRegistry::GetInstance()),
+      dataHandle(registry.GetDataHandle()),
+      liveWindowTable(
+          nt::NetworkTableInstance::GetDefault().GetTable("LiveWindow")) {
+  statusTable = liveWindowTable->GetSubTable(".status");
+  enabledEntry = statusTable->GetEntry("LW Enabled");
+}
+
+std::shared_ptr<LiveWindow::Impl::Component> LiveWindow::Impl::GetOrAdd(
+    Sendable* sendable) {
+  auto data = std::static_pointer_cast<Component>(
+      registry.GetData(sendable, dataHandle));
+  if (!data) {
+    data = std::make_shared<Component>();
+    registry.SetData(sendable, dataHandle, data);
+  }
+  return data;
+}
+
+LiveWindow* LiveWindow::GetInstance() {
+  static LiveWindow instance;
+  return &instance;
+}
+
+void LiveWindow::EnableTelemetry(Sendable* sendable) {
+  std::scoped_lock lock(m_impl->mutex);
+  // Re-enable global setting in case DisableAllTelemetry() was called.
+  m_impl->telemetryEnabled = true;
+  m_impl->GetOrAdd(sendable)->telemetryEnabled = true;
+}
+
+void LiveWindow::DisableTelemetry(Sendable* sendable) {
+  std::scoped_lock lock(m_impl->mutex);
+  m_impl->GetOrAdd(sendable)->telemetryEnabled = false;
+}
+
+void LiveWindow::DisableAllTelemetry() {
+  std::scoped_lock lock(m_impl->mutex);
+  m_impl->telemetryEnabled = false;
+  m_impl->registry.ForeachLiveWindow(m_impl->dataHandle, [&](auto& cbdata) {
+    if (!cbdata.data) cbdata.data = std::make_shared<Impl::Component>();
+    std::static_pointer_cast<Impl::Component>(cbdata.data)->telemetryEnabled =
+        false;
+  });
+}
+
+bool LiveWindow::IsEnabled() const {
+  std::scoped_lock lock(m_impl->mutex);
+  return m_impl->liveWindowEnabled;
+}
+
+void LiveWindow::SetEnabled(bool enabled) {
+  std::scoped_lock lock(m_impl->mutex);
+  if (m_impl->liveWindowEnabled == enabled) return;
+  m_impl->startLiveWindow = enabled;
+  m_impl->liveWindowEnabled = enabled;
+  // Force table generation now to make sure everything is defined
+  UpdateValuesUnsafe();
+  if (enabled) {
+  } else {
+    m_impl->registry.ForeachLiveWindow(m_impl->dataHandle, [&](auto& cbdata) {
+      cbdata.builder.StopLiveWindowMode();
+    });
+  }
+  m_impl->enabledEntry.SetBoolean(enabled);
+}
+
+void LiveWindow::UpdateValues() {
+  std::scoped_lock lock(m_impl->mutex);
+  UpdateValuesUnsafe();
+}
+
+void LiveWindow::UpdateValuesUnsafe() {
+  // Only do this if either LiveWindow mode or telemetry is enabled.
+  if (!m_impl->liveWindowEnabled && !m_impl->telemetryEnabled) return;
+
+  m_impl->registry.ForeachLiveWindow(m_impl->dataHandle, [&](auto& cbdata) {
+    if (!cbdata.sendable || cbdata.parent) return;
+
+    if (!cbdata.data) cbdata.data = std::make_shared<Impl::Component>();
+
+    auto& comp = *std::static_pointer_cast<Impl::Component>(cbdata.data);
+
+    if (!m_impl->liveWindowEnabled && !comp.telemetryEnabled) return;
+
+    if (comp.firstTime) {
+      // By holding off creating the NetworkTable entries, it allows the
+      // components to be redefined. This allows default sensor and actuator
+      // values to be created that are replaced with the custom names from
+      // users calling setName.
+      if (cbdata.name.empty()) return;
+      auto ssTable = m_impl->liveWindowTable->GetSubTable(cbdata.subsystem);
+      std::shared_ptr<NetworkTable> table;
+      // Treat name==subsystem as top level of subsystem
+      if (cbdata.name == cbdata.subsystem)
+        table = ssTable;
+      else
+        table = ssTable->GetSubTable(cbdata.name);
+      table->GetEntry(".name").SetString(cbdata.name);
+      cbdata.builder.SetTable(table);
+      cbdata.sendable->InitSendable(cbdata.builder);
+      ssTable->GetEntry(".type").SetString("LW Subsystem");
+
+      comp.firstTime = false;
+    }
+
+    if (m_impl->startLiveWindow) cbdata.builder.StartLiveWindowMode();
+    cbdata.builder.UpdateTable();
+  });
+
+  m_impl->startLiveWindow = false;
+}
+
+LiveWindow::LiveWindow() : m_impl(new Impl) {}
diff --git a/wpilibc/src/main/native/cpp/shuffleboard/ComplexWidget.cpp b/wpilibc/src/main/native/cpp/shuffleboard/ComplexWidget.cpp
new file mode 100644
index 0000000..19e17bb
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/shuffleboard/ComplexWidget.cpp
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/ComplexWidget.h"
+
+#include "frc/smartdashboard/Sendable.h"
+
+using namespace frc;
+
+ComplexWidget::ComplexWidget(ShuffleboardContainer& parent,
+                             const wpi::Twine& title, Sendable& sendable)
+    : ShuffleboardValue(title),
+      ShuffleboardWidget(parent, title),
+      m_sendable(sendable) {}
+
+void ComplexWidget::EnableIfActuator() {
+  if (m_builder.IsActuator()) {
+    m_builder.StartLiveWindowMode();
+  }
+}
+
+void ComplexWidget::DisableIfActuator() {
+  if (m_builder.IsActuator()) {
+    m_builder.StopLiveWindowMode();
+  }
+}
+
+void ComplexWidget::BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                              std::shared_ptr<nt::NetworkTable> metaTable) {
+  BuildMetadata(metaTable);
+  if (!m_builderInit) {
+    m_builder.SetTable(parentTable->GetSubTable(GetTitle()));
+    m_sendable.InitSendable(m_builder);
+    m_builder.StartListeners();
+    m_builderInit = true;
+  }
+  m_builder.UpdateTable();
+}
diff --git a/wpilibc/src/main/native/cpp/shuffleboard/LayoutType.cpp b/wpilibc/src/main/native/cpp/shuffleboard/LayoutType.cpp
new file mode 100644
index 0000000..a21cad9
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/shuffleboard/LayoutType.cpp
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/LayoutType.h"
+
+using namespace frc;
+
+wpi::StringRef LayoutType::GetLayoutName() const { return m_layoutName; }
diff --git a/wpilibc/src/main/native/cpp/shuffleboard/RecordingController.cpp b/wpilibc/src/main/native/cpp/shuffleboard/RecordingController.cpp
new file mode 100644
index 0000000..d80001e
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/shuffleboard/RecordingController.cpp
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/RecordingController.h"
+
+#include "frc/DriverStation.h"
+
+using namespace frc;
+using namespace frc::detail;
+
+RecordingController::RecordingController(nt::NetworkTableInstance ntInstance)
+    : m_recordingControlEntry(), m_recordingFileNameFormatEntry() {
+  m_recordingControlEntry =
+      ntInstance.GetEntry("/Shuffleboard/.recording/RecordData");
+  m_recordingFileNameFormatEntry =
+      ntInstance.GetEntry("/Shuffleboard/.recording/FileNameFormat");
+  m_eventsTable = ntInstance.GetTable("/Shuffleboard/.recording/events");
+}
+
+void RecordingController::StartRecording() {
+  m_recordingControlEntry.SetBoolean(true);
+}
+
+void RecordingController::StopRecording() {
+  m_recordingControlEntry.SetBoolean(false);
+}
+
+void RecordingController::SetRecordingFileNameFormat(wpi::StringRef format) {
+  m_recordingFileNameFormatEntry.SetString(format);
+}
+
+void RecordingController::ClearRecordingFileNameFormat() {
+  m_recordingFileNameFormatEntry.Delete();
+}
+
+void RecordingController::AddEventMarker(
+    wpi::StringRef name, wpi::StringRef description,
+    ShuffleboardEventImportance importance) {
+  if (name.empty()) {
+    DriverStation::ReportError("Shuffleboard event name was not specified");
+    return;
+  }
+  m_eventsTable->GetSubTable(name)->GetEntry("Info").SetStringArray(
+      {description, ShuffleboardEventImportanceName(importance)});
+}
diff --git a/wpilibc/src/main/native/cpp/shuffleboard/SendableCameraWrapper.cpp b/wpilibc/src/main/native/cpp/shuffleboard/SendableCameraWrapper.cpp
new file mode 100644
index 0000000..b6f8ce9
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/shuffleboard/SendableCameraWrapper.cpp
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/SendableCameraWrapper.h"
+
+#include <functional>
+#include <memory>
+#include <string>
+
+#include <wpi/DenseMap.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+namespace frc {
+namespace detail {
+std::shared_ptr<SendableCameraWrapper>& GetSendableCameraWrapper(
+    CS_Source source) {
+  static wpi::DenseMap<int, std::shared_ptr<SendableCameraWrapper>> wrappers;
+  return wrappers[static_cast<int>(source)];
+}
+
+void AddToSendableRegistry(frc::Sendable* sendable, std::string name) {
+  SendableRegistry::GetInstance().Add(sendable, name);
+}
+}  // namespace detail
+
+void SendableCameraWrapper::InitSendable(SendableBuilder& builder) {
+  builder.AddStringProperty(".ShuffleboardURI", [this] { return m_uri; },
+                            nullptr);
+}
+}  // namespace frc
diff --git a/wpilibc/src/main/native/cpp/shuffleboard/Shuffleboard.cpp b/wpilibc/src/main/native/cpp/shuffleboard/Shuffleboard.cpp
new file mode 100644
index 0000000..2d69847
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/shuffleboard/Shuffleboard.cpp
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/Shuffleboard.h"
+
+#include <networktables/NetworkTableInstance.h>
+
+#include "frc/shuffleboard/ShuffleboardTab.h"
+
+using namespace frc;
+
+void Shuffleboard::Update() { GetInstance().Update(); }
+
+ShuffleboardTab& Shuffleboard::GetTab(wpi::StringRef title) {
+  return GetInstance().GetTab(title);
+}
+
+void Shuffleboard::SelectTab(int index) { GetInstance().SelectTab(index); }
+
+void Shuffleboard::SelectTab(wpi::StringRef title) {
+  GetInstance().SelectTab(title);
+}
+
+void Shuffleboard::EnableActuatorWidgets() {
+  GetInstance().EnableActuatorWidgets();
+}
+
+void Shuffleboard::DisableActuatorWidgets() {
+  // Need to update to make sure the sendable builders are initialized
+  Update();
+  GetInstance().DisableActuatorWidgets();
+}
+
+void Shuffleboard::StartRecording() {
+  GetRecordingController().StartRecording();
+}
+
+void Shuffleboard::StopRecording() { GetRecordingController().StopRecording(); }
+
+void Shuffleboard::SetRecordingFileNameFormat(wpi::StringRef format) {
+  GetRecordingController().SetRecordingFileNameFormat(format);
+}
+
+void Shuffleboard::ClearRecordingFileNameFormat() {
+  GetRecordingController().ClearRecordingFileNameFormat();
+}
+
+void Shuffleboard::AddEventMarker(wpi::StringRef name,
+                                  wpi::StringRef description,
+                                  ShuffleboardEventImportance importance) {
+  GetRecordingController().AddEventMarker(name, description, importance);
+}
+
+void Shuffleboard::AddEventMarker(wpi::StringRef name,
+                                  ShuffleboardEventImportance importance) {
+  AddEventMarker(name, "", importance);
+}
+
+detail::ShuffleboardInstance& Shuffleboard::GetInstance() {
+  static detail::ShuffleboardInstance inst(
+      nt::NetworkTableInstance::GetDefault());
+  return inst;
+}
+
+detail::RecordingController& Shuffleboard::GetRecordingController() {
+  static detail::RecordingController inst(
+      nt::NetworkTableInstance::GetDefault());
+  return inst;
+}
diff --git a/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardComponentBase.cpp b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardComponentBase.cpp
new file mode 100644
index 0000000..7617333
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardComponentBase.cpp
@@ -0,0 +1,76 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/ShuffleboardComponentBase.h"
+
+#include <wpi/SmallVector.h>
+
+using namespace frc;
+
+ShuffleboardComponentBase::ShuffleboardComponentBase(
+    ShuffleboardContainer& parent, const wpi::Twine& title,
+    const wpi::Twine& type)
+    : ShuffleboardValue(title), m_parent(parent) {
+  wpi::SmallVector<char, 16> storage;
+  m_type = type.toStringRef(storage);
+}
+
+void ShuffleboardComponentBase::SetType(const wpi::Twine& type) {
+  wpi::SmallVector<char, 16> storage;
+  m_type = type.toStringRef(storage);
+  m_metadataDirty = true;
+}
+
+void ShuffleboardComponentBase::BuildMetadata(
+    std::shared_ptr<nt::NetworkTable> metaTable) {
+  if (!m_metadataDirty) {
+    return;
+  }
+  // Component type
+  if (GetType() == "") {
+    metaTable->GetEntry("PreferredComponent").Delete();
+  } else {
+    metaTable->GetEntry("PreferredComponent").ForceSetString(GetType());
+  }
+
+  // Tile size
+  if (m_width <= 0 || m_height <= 0) {
+    metaTable->GetEntry("Size").Delete();
+  } else {
+    metaTable->GetEntry("Size").SetDoubleArray(
+        {static_cast<double>(m_width), static_cast<double>(m_height)});
+  }
+
+  // Tile position
+  if (m_column < 0 || m_row < 0) {
+    metaTable->GetEntry("Position").Delete();
+  } else {
+    metaTable->GetEntry("Position")
+        .SetDoubleArray(
+            {static_cast<double>(m_column), static_cast<double>(m_row)});
+  }
+
+  // Custom properties
+  if (GetProperties().size() > 0) {
+    auto propTable = metaTable->GetSubTable("Properties");
+    for (auto& entry : GetProperties()) {
+      propTable->GetEntry(entry.first()).SetValue(entry.second);
+    }
+  }
+  m_metadataDirty = false;
+}
+
+ShuffleboardContainer& ShuffleboardComponentBase::GetParent() {
+  return m_parent;
+}
+
+const std::string& ShuffleboardComponentBase::GetType() const { return m_type; }
+
+const wpi::StringMap<std::shared_ptr<nt::Value>>&
+ShuffleboardComponentBase::GetProperties() const {
+  return m_properties;
+}
diff --git a/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp
new file mode 100644
index 0000000..bb9dc9e
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp
@@ -0,0 +1,300 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/ShuffleboardContainer.h"
+
+#include <wpi/SmallVector.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/shuffleboard/ComplexWidget.h"
+#include "frc/shuffleboard/ShuffleboardComponent.h"
+#include "frc/shuffleboard/ShuffleboardLayout.h"
+#include "frc/shuffleboard/SimpleWidget.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+static constexpr const char* layoutStrings[] = {"List Layout", "Grid Layout"};
+
+static constexpr const char* GetStringFromBuiltInLayout(BuiltInLayouts layout) {
+  return layoutStrings[static_cast<int>(layout)];
+}
+
+ShuffleboardContainer::ShuffleboardContainer(const wpi::Twine& title)
+    : ShuffleboardValue(title) {}
+
+const std::vector<std::unique_ptr<ShuffleboardComponentBase>>&
+ShuffleboardContainer::GetComponents() const {
+  return m_components;
+}
+
+ShuffleboardLayout& ShuffleboardContainer::GetLayout(const wpi::Twine& title,
+                                                     BuiltInLayouts type) {
+  return GetLayout(title, GetStringFromBuiltInLayout(type));
+}
+
+ShuffleboardLayout& ShuffleboardContainer::GetLayout(const wpi::Twine& title,
+                                                     const LayoutType& type) {
+  return GetLayout(title, type.GetLayoutName());
+}
+
+ShuffleboardLayout& ShuffleboardContainer::GetLayout(const wpi::Twine& title,
+                                                     const wpi::Twine& type) {
+  wpi::SmallVector<char, 16> storage;
+  auto titleRef = title.toStringRef(storage);
+  if (m_layouts.count(titleRef) == 0) {
+    auto layout = std::make_unique<ShuffleboardLayout>(*this, type, titleRef);
+    auto ptr = layout.get();
+    m_components.emplace_back(std::move(layout));
+    m_layouts.insert(std::make_pair(titleRef, ptr));
+  }
+  return *m_layouts[titleRef];
+}
+
+ShuffleboardLayout& ShuffleboardContainer::GetLayout(const wpi::Twine& title) {
+  wpi::SmallVector<char, 16> storage;
+  auto titleRef = title.toStringRef(storage);
+  if (m_layouts.count(titleRef) == 0) {
+    wpi_setWPIErrorWithContext(
+        InvalidParameter, "No layout with the given title has been defined");
+  }
+  return *m_layouts[titleRef];
+}
+
+ComplexWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                          Sendable& sendable) {
+  CheckTitle(title);
+  auto widget = std::make_unique<ComplexWidget>(*this, title, sendable);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  return *ptr;
+}
+
+ComplexWidget& ShuffleboardContainer::Add(Sendable& sendable) {
+  auto name = SendableRegistry::GetInstance().GetName(&sendable);
+  if (name.empty()) {
+    wpi::outs() << "Sendable must have a name\n";
+  }
+  return Add(name, sendable);
+}
+
+SimpleWidget& ShuffleboardContainer::Add(
+    const wpi::Twine& title, std::shared_ptr<nt::Value> defaultValue) {
+  CheckTitle(title);
+
+  auto widget = std::make_unique<SimpleWidget>(*this, title);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  ptr->GetEntry().SetDefaultValue(defaultValue);
+  return *ptr;
+}
+
+SimpleWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                         bool defaultValue) {
+  return Add(title, nt::Value::MakeBoolean(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                         double defaultValue) {
+  return Add(title, nt::Value::MakeDouble(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                         int defaultValue) {
+  return Add(title, nt::Value::MakeDouble(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                         const wpi::Twine& defaultValue) {
+  return Add(title, nt::Value::MakeString(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                         const char* defaultValue) {
+  return Add(title, nt::Value::MakeString(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                         wpi::ArrayRef<bool> defaultValue) {
+  return Add(title, nt::Value::MakeBooleanArray(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                         wpi::ArrayRef<double> defaultValue) {
+  return Add(title, nt::Value::MakeDoubleArray(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(
+    const wpi::Twine& title, wpi::ArrayRef<std::string> defaultValue) {
+  return Add(title, nt::Value::MakeStringArray(defaultValue));
+}
+
+SuppliedValueWidget<std::string>& ShuffleboardContainer::AddString(
+    const wpi::Twine& title, std::function<std::string()> supplier) {
+  static auto setter = [](nt::NetworkTableEntry entry, std::string value) {
+    entry.SetString(value);
+  };
+
+  CheckTitle(title);
+  auto widget = std::make_unique<SuppliedValueWidget<std::string>>(
+      *this, title, supplier, setter);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  return *ptr;
+}
+
+SuppliedValueWidget<double>& ShuffleboardContainer::AddNumber(
+    const wpi::Twine& title, std::function<double()> supplier) {
+  static auto setter = [](nt::NetworkTableEntry entry, double value) {
+    entry.SetDouble(value);
+  };
+
+  CheckTitle(title);
+  auto widget = std::make_unique<SuppliedValueWidget<double>>(*this, title,
+                                                              supplier, setter);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  return *ptr;
+}
+
+SuppliedValueWidget<bool>& ShuffleboardContainer::AddBoolean(
+    const wpi::Twine& title, std::function<bool()> supplier) {
+  static auto setter = [](nt::NetworkTableEntry entry, bool value) {
+    entry.SetBoolean(value);
+  };
+
+  CheckTitle(title);
+  auto widget = std::make_unique<SuppliedValueWidget<bool>>(*this, title,
+                                                            supplier, setter);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  return *ptr;
+}
+
+SuppliedValueWidget<std::vector<std::string>>&
+ShuffleboardContainer::AddStringArray(
+    const wpi::Twine& title,
+    std::function<std::vector<std::string>()> supplier) {
+  static auto setter = [](nt::NetworkTableEntry entry,
+                          std::vector<std::string> value) {
+    entry.SetStringArray(value);
+  };
+
+  CheckTitle(title);
+  auto widget = std::make_unique<SuppliedValueWidget<std::vector<std::string>>>(
+      *this, title, supplier, setter);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  return *ptr;
+}
+
+SuppliedValueWidget<std::vector<double>>& ShuffleboardContainer::AddNumberArray(
+    const wpi::Twine& title, std::function<std::vector<double>()> supplier) {
+  static auto setter = [](nt::NetworkTableEntry entry,
+                          std::vector<double> value) {
+    entry.SetDoubleArray(value);
+  };
+
+  CheckTitle(title);
+  auto widget = std::make_unique<SuppliedValueWidget<std::vector<double>>>(
+      *this, title, supplier, setter);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  return *ptr;
+}
+
+SuppliedValueWidget<std::vector<int>>& ShuffleboardContainer::AddBooleanArray(
+    const wpi::Twine& title, std::function<std::vector<int>()> supplier) {
+  static auto setter = [](nt::NetworkTableEntry entry, std::vector<int> value) {
+    entry.SetBooleanArray(value);
+  };
+
+  CheckTitle(title);
+  auto widget = std::make_unique<SuppliedValueWidget<std::vector<int>>>(
+      *this, title, supplier, setter);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  return *ptr;
+}
+
+SuppliedValueWidget<wpi::StringRef>& ShuffleboardContainer::AddRaw(
+    const wpi::Twine& title, std::function<wpi::StringRef()> supplier) {
+  static auto setter = [](nt::NetworkTableEntry entry, wpi::StringRef value) {
+    entry.SetRaw(value);
+  };
+
+  CheckTitle(title);
+  auto widget = std::make_unique<SuppliedValueWidget<wpi::StringRef>>(
+      *this, title, supplier, setter);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  return *ptr;
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(
+    const wpi::Twine& title, std::shared_ptr<nt::Value> defaultValue) {
+  auto& widget = Add(title, defaultValue);
+  widget.GetEntry().SetPersistent();
+  return widget;
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(const wpi::Twine& title,
+                                                   bool defaultValue) {
+  return AddPersistent(title, nt::Value::MakeBoolean(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(const wpi::Twine& title,
+                                                   double defaultValue) {
+  return AddPersistent(title, nt::Value::MakeDouble(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(const wpi::Twine& title,
+                                                   int defaultValue) {
+  return AddPersistent(title, nt::Value::MakeDouble(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(
+    const wpi::Twine& title, const wpi::Twine& defaultValue) {
+  return AddPersistent(title, nt::Value::MakeString(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(
+    const wpi::Twine& title, wpi::ArrayRef<bool> defaultValue) {
+  return AddPersistent(title, nt::Value::MakeBooleanArray(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(
+    const wpi::Twine& title, wpi::ArrayRef<double> defaultValue) {
+  return AddPersistent(title, nt::Value::MakeDoubleArray(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(
+    const wpi::Twine& title, wpi::ArrayRef<std::string> defaultValue) {
+  return AddPersistent(title, nt::Value::MakeStringArray(defaultValue));
+}
+
+void ShuffleboardContainer::EnableIfActuator() {
+  for (auto& component : GetComponents()) {
+    component->EnableIfActuator();
+  }
+}
+
+void ShuffleboardContainer::DisableIfActuator() {
+  for (auto& component : GetComponents()) {
+    component->DisableIfActuator();
+  }
+}
+
+void ShuffleboardContainer::CheckTitle(const wpi::Twine& title) {
+  wpi::SmallVector<char, 16> storage;
+  auto titleRef = title.toStringRef(storage);
+  if (m_usedTitles.count(titleRef) > 0) {
+    wpi::errs() << "Title is already in use: " << title << "\n";
+    return;
+  }
+  m_usedTitles.insert(titleRef);
+}
diff --git a/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardInstance.cpp b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardInstance.cpp
new file mode 100644
index 0000000..9717a8e
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardInstance.cpp
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/ShuffleboardInstance.h"
+
+#include <hal/FRCUsageReporting.h>
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/StringMap.h>
+
+#include "frc/shuffleboard/Shuffleboard.h"
+
+using namespace frc::detail;
+
+struct ShuffleboardInstance::Impl {
+  wpi::StringMap<ShuffleboardTab> tabs;
+
+  bool tabsChanged = false;
+  std::shared_ptr<nt::NetworkTable> rootTable;
+  std::shared_ptr<nt::NetworkTable> rootMetaTable;
+};
+
+ShuffleboardInstance::ShuffleboardInstance(nt::NetworkTableInstance ntInstance)
+    : m_impl(new Impl) {
+  m_impl->rootTable = ntInstance.GetTable(Shuffleboard::kBaseTableName);
+  m_impl->rootMetaTable = m_impl->rootTable->GetSubTable(".metadata");
+  HAL_Report(HALUsageReporting::kResourceType_Shuffleboard, 0);
+}
+
+ShuffleboardInstance::~ShuffleboardInstance() {}
+
+frc::ShuffleboardTab& ShuffleboardInstance::GetTab(wpi::StringRef title) {
+  if (m_impl->tabs.find(title) == m_impl->tabs.end()) {
+    m_impl->tabs.try_emplace(title, ShuffleboardTab(*this, title));
+    m_impl->tabsChanged = true;
+  }
+  return m_impl->tabs.find(title)->second;
+}
+
+void ShuffleboardInstance::Update() {
+  if (m_impl->tabsChanged) {
+    std::vector<std::string> tabTitles;
+    for (auto& entry : m_impl->tabs) {
+      tabTitles.emplace_back(entry.second.GetTitle());
+    }
+    m_impl->rootMetaTable->GetEntry("Tabs").ForceSetStringArray(tabTitles);
+    m_impl->tabsChanged = false;
+  }
+  for (auto& entry : m_impl->tabs) {
+    auto& tab = entry.second;
+    tab.BuildInto(m_impl->rootTable,
+                  m_impl->rootMetaTable->GetSubTable(tab.GetTitle()));
+  }
+}
+
+void ShuffleboardInstance::EnableActuatorWidgets() {
+  for (auto& entry : m_impl->tabs) {
+    auto& tab = entry.second;
+    for (auto& component : tab.GetComponents()) {
+      component->EnableIfActuator();
+    }
+  }
+}
+
+void ShuffleboardInstance::DisableActuatorWidgets() {
+  for (auto& entry : m_impl->tabs) {
+    auto& tab = entry.second;
+    for (auto& component : tab.GetComponents()) {
+      component->DisableIfActuator();
+    }
+  }
+}
+
+void ShuffleboardInstance::SelectTab(int index) {
+  m_impl->rootMetaTable->GetEntry("Selected").ForceSetDouble(index);
+}
+
+void ShuffleboardInstance::SelectTab(wpi::StringRef title) {
+  m_impl->rootMetaTable->GetEntry("Selected").ForceSetString(title);
+}
diff --git a/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardLayout.cpp b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardLayout.cpp
new file mode 100644
index 0000000..8418b77
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardLayout.cpp
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/ShuffleboardLayout.h"
+
+using namespace frc;
+
+ShuffleboardLayout::ShuffleboardLayout(ShuffleboardContainer& parent,
+                                       const wpi::Twine& name,
+                                       const wpi::Twine& type)
+    : ShuffleboardValue(type),
+      ShuffleboardComponent(parent, type, name),
+      ShuffleboardContainer(name) {
+  m_isLayout = true;
+}
+
+void ShuffleboardLayout::BuildInto(
+    std::shared_ptr<nt::NetworkTable> parentTable,
+    std::shared_ptr<nt::NetworkTable> metaTable) {
+  BuildMetadata(metaTable);
+  auto table = parentTable->GetSubTable(GetTitle());
+  table->GetEntry(".type").SetString("ShuffleboardLayout");
+  for (auto& component : GetComponents()) {
+    component->BuildInto(table, metaTable->GetSubTable(component->GetTitle()));
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardTab.cpp b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardTab.cpp
new file mode 100644
index 0000000..7a8338e
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardTab.cpp
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/ShuffleboardTab.h"
+
+using namespace frc;
+
+ShuffleboardTab::ShuffleboardTab(ShuffleboardRoot& root, wpi::StringRef title)
+    : ShuffleboardValue(title), ShuffleboardContainer(title), m_root(root) {}
+
+ShuffleboardRoot& ShuffleboardTab::GetRoot() { return m_root; }
+
+void ShuffleboardTab::BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                                std::shared_ptr<nt::NetworkTable> metaTable) {
+  auto tabTable = parentTable->GetSubTable(GetTitle());
+  tabTable->GetEntry(".type").SetString("ShuffleboardTab");
+  for (auto& component : GetComponents()) {
+    component->BuildInto(tabTable,
+                         metaTable->GetSubTable(component->GetTitle()));
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardWidget.cpp b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardWidget.cpp
new file mode 100644
index 0000000..3b79a9c
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardWidget.cpp
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/ShuffleboardWidget.h"
+
+using namespace frc;
+
+static constexpr const char* widgetStrings[] = {
+    "Text View",
+    "Number Slider",
+    "Number Bar",
+    "Simple Dial",
+    "Graph",
+    "Boolean Box",
+    "Toggle Button",
+    "Toggle Switch",
+    "Voltage View",
+    "PDP",
+    "ComboBox Chooser",
+    "Split Button Chooser",
+    "Encoder",
+    "Speed Controller",
+    "Command",
+    "PID Command",
+    "PID Controller",
+    "Accelerometer",
+    "3-Axis Accelerometer",
+    "Gyro",
+    "Relay",
+    "Differential Drivebase",
+    "Mecanum Drivebase",
+    "Camera Stream",
+};
+
+const char* detail::GetStringForWidgetType(BuiltInWidgets type) {
+  return widgetStrings[static_cast<int>(type)];
+}
diff --git a/wpilibc/src/main/native/cpp/shuffleboard/SimpleWidget.cpp b/wpilibc/src/main/native/cpp/shuffleboard/SimpleWidget.cpp
new file mode 100644
index 0000000..89af25d
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/shuffleboard/SimpleWidget.cpp
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/SimpleWidget.h"
+
+#include "frc/shuffleboard/Shuffleboard.h"
+#include "frc/shuffleboard/ShuffleboardLayout.h"
+#include "frc/shuffleboard/ShuffleboardTab.h"
+
+using namespace frc;
+
+SimpleWidget::SimpleWidget(ShuffleboardContainer& parent,
+                           const wpi::Twine& title)
+    : ShuffleboardValue(title), ShuffleboardWidget(parent, title), m_entry() {}
+
+nt::NetworkTableEntry SimpleWidget::GetEntry() {
+  if (!m_entry) {
+    ForceGenerate();
+  }
+  return m_entry;
+}
+
+void SimpleWidget::BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                             std::shared_ptr<nt::NetworkTable> metaTable) {
+  BuildMetadata(metaTable);
+  if (!m_entry) {
+    m_entry = parentTable->GetEntry(GetTitle());
+  }
+}
+
+void SimpleWidget::ForceGenerate() {
+  ShuffleboardContainer* parent = &GetParent();
+
+  while (parent->m_isLayout) {
+    parent = &(static_cast<ShuffleboardLayout*>(parent)->GetParent());
+  }
+
+  auto& tab = *static_cast<ShuffleboardTab*>(parent);
+  tab.GetRoot().Update();
+}
diff --git a/wpilibc/src/main/native/cpp/shuffleboard/WidgetType.cpp b/wpilibc/src/main/native/cpp/shuffleboard/WidgetType.cpp
new file mode 100644
index 0000000..cb73d30
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/shuffleboard/WidgetType.cpp
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/WidgetType.h"
+
+using namespace frc;
+
+wpi::StringRef WidgetType::GetWidgetName() const { return m_widgetName; }
diff --git a/wpilibc/src/main/native/cpp/smartdashboard/ListenerExecutor.cpp b/wpilibc/src/main/native/cpp/smartdashboard/ListenerExecutor.cpp
new file mode 100644
index 0000000..75b373a
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/smartdashboard/ListenerExecutor.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/smartdashboard/ListenerExecutor.h"
+
+using namespace frc::detail;
+
+void ListenerExecutor::Execute(std::function<void()> task) {
+  std::scoped_lock lock(m_lock);
+  m_tasks.emplace_back(task);
+}
+
+void ListenerExecutor::RunListenerTasks() {
+  // Locally copy tasks from internal list; minimizes blocking time
+  {
+    std::scoped_lock lock(m_lock);
+    std::swap(m_tasks, m_runningTasks);
+  }
+
+  for (auto&& task : m_runningTasks) {
+    task();
+  }
+  m_runningTasks.clear();
+}
diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SendableBase.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SendableBase.cpp
new file mode 100644
index 0000000..7fc8635
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/smartdashboard/SendableBase.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/smartdashboard/SendableBase.h"
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+SendableBase::SendableBase(bool addLiveWindow) {
+  if (addLiveWindow)
+    SendableRegistry::GetInstance().AddLW(this, "");
+  else
+    SendableRegistry::GetInstance().Add(this, "");
+}
diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp
new file mode 100644
index 0000000..d075deb
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp
@@ -0,0 +1,402 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/smartdashboard/SendableBuilderImpl.h"
+
+#include <ntcore_cpp.h>
+#include <wpi/SmallString.h>
+
+#include "frc/smartdashboard/SmartDashboard.h"
+
+using namespace frc;
+
+void SendableBuilderImpl::SetTable(std::shared_ptr<nt::NetworkTable> table) {
+  m_table = table;
+  m_controllableEntry = table->GetEntry(".controllable");
+}
+
+std::shared_ptr<nt::NetworkTable> SendableBuilderImpl::GetTable() {
+  return m_table;
+}
+
+bool SendableBuilderImpl::HasTable() const { return m_table != nullptr; }
+
+bool SendableBuilderImpl::IsActuator() const { return m_actuator; }
+
+void SendableBuilderImpl::UpdateTable() {
+  uint64_t time = nt::Now();
+  for (auto& property : m_properties) {
+    if (property.update) property.update(property.entry, time);
+  }
+  if (m_updateTable) m_updateTable();
+}
+
+void SendableBuilderImpl::StartListeners() {
+  for (auto& property : m_properties) property.StartListener();
+  if (m_controllableEntry) m_controllableEntry.SetBoolean(true);
+}
+
+void SendableBuilderImpl::StopListeners() {
+  for (auto& property : m_properties) property.StopListener();
+  if (m_controllableEntry) m_controllableEntry.SetBoolean(false);
+}
+
+void SendableBuilderImpl::StartLiveWindowMode() {
+  if (m_safeState) m_safeState();
+  StartListeners();
+}
+
+void SendableBuilderImpl::StopLiveWindowMode() {
+  StopListeners();
+  if (m_safeState) m_safeState();
+}
+
+void SendableBuilderImpl::ClearProperties() { m_properties.clear(); }
+
+void SendableBuilderImpl::SetSmartDashboardType(const wpi::Twine& type) {
+  m_table->GetEntry(".type").SetString(type);
+}
+
+void SendableBuilderImpl::SetActuator(bool value) {
+  m_table->GetEntry(".actuator").SetBoolean(value);
+  m_actuator = value;
+}
+
+void SendableBuilderImpl::SetSafeState(std::function<void()> func) {
+  m_safeState = func;
+}
+
+void SendableBuilderImpl::SetUpdateTable(std::function<void()> func) {
+  m_updateTable = func;
+}
+
+nt::NetworkTableEntry SendableBuilderImpl::GetEntry(const wpi::Twine& key) {
+  return m_table->GetEntry(key);
+}
+
+void SendableBuilderImpl::AddBooleanProperty(const wpi::Twine& key,
+                                             std::function<bool()> getter,
+                                             std::function<void(bool)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(nt::Value::MakeBoolean(getter(), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsBoolean()) return;
+            SmartDashboard::PostListenerTask(
+                [=] { setter(event.value->GetBoolean()); });
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddDoubleProperty(
+    const wpi::Twine& key, std::function<double()> getter,
+    std::function<void(double)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(nt::Value::MakeDouble(getter(), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsDouble()) return;
+            SmartDashboard::PostListenerTask(
+                [=] { setter(event.value->GetDouble()); });
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddStringProperty(
+    const wpi::Twine& key, std::function<std::string()> getter,
+    std::function<void(wpi::StringRef)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(nt::Value::MakeString(getter(), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsString()) return;
+            SmartDashboard::PostListenerTask(
+                [=] { setter(event.value->GetString()); });
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddBooleanArrayProperty(
+    const wpi::Twine& key, std::function<std::vector<int>()> getter,
+    std::function<void(wpi::ArrayRef<int>)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(nt::Value::MakeBooleanArray(getter(), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsBooleanArray()) return;
+            SmartDashboard::PostListenerTask(
+                [=] { setter(event.value->GetBooleanArray()); });
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddDoubleArrayProperty(
+    const wpi::Twine& key, std::function<std::vector<double>()> getter,
+    std::function<void(wpi::ArrayRef<double>)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(nt::Value::MakeDoubleArray(getter(), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsDoubleArray()) return;
+            SmartDashboard::PostListenerTask(
+                [=] { setter(event.value->GetDoubleArray()); });
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddStringArrayProperty(
+    const wpi::Twine& key, std::function<std::vector<std::string>()> getter,
+    std::function<void(wpi::ArrayRef<std::string>)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(nt::Value::MakeStringArray(getter(), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsStringArray()) return;
+            SmartDashboard::PostListenerTask(
+                [=] { setter(event.value->GetStringArray()); });
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddRawProperty(
+    const wpi::Twine& key, std::function<std::string()> getter,
+    std::function<void(wpi::StringRef)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(nt::Value::MakeRaw(getter(), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsRaw()) return;
+            SmartDashboard::PostListenerTask(
+                [=] { setter(event.value->GetRaw()); });
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddValueProperty(
+    const wpi::Twine& key, std::function<std::shared_ptr<nt::Value>()> getter,
+    std::function<void(std::shared_ptr<nt::Value>)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(getter());
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            SmartDashboard::PostListenerTask([=] { setter(event.value); });
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddSmallStringProperty(
+    const wpi::Twine& key,
+    std::function<wpi::StringRef(wpi::SmallVectorImpl<char>& buf)> getter,
+    std::function<void(wpi::StringRef)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      wpi::SmallString<128> buf;
+      entry.SetValue(nt::Value::MakeString(getter(buf), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsString()) return;
+            SmartDashboard::PostListenerTask(
+                [=] { setter(event.value->GetString()); });
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddSmallBooleanArrayProperty(
+    const wpi::Twine& key,
+    std::function<wpi::ArrayRef<int>(wpi::SmallVectorImpl<int>& buf)> getter,
+    std::function<void(wpi::ArrayRef<int>)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      wpi::SmallVector<int, 16> buf;
+      entry.SetValue(nt::Value::MakeBooleanArray(getter(buf), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsBooleanArray()) return;
+            SmartDashboard::PostListenerTask(
+                [=] { setter(event.value->GetBooleanArray()); });
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddSmallDoubleArrayProperty(
+    const wpi::Twine& key,
+    std::function<wpi::ArrayRef<double>(wpi::SmallVectorImpl<double>& buf)>
+        getter,
+    std::function<void(wpi::ArrayRef<double>)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      wpi::SmallVector<double, 16> buf;
+      entry.SetValue(nt::Value::MakeDoubleArray(getter(buf), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsDoubleArray()) return;
+            SmartDashboard::PostListenerTask(
+                [=] { setter(event.value->GetDoubleArray()); });
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddSmallStringArrayProperty(
+    const wpi::Twine& key,
+    std::function<
+        wpi::ArrayRef<std::string>(wpi::SmallVectorImpl<std::string>& buf)>
+        getter,
+    std::function<void(wpi::ArrayRef<std::string>)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      wpi::SmallVector<std::string, 16> buf;
+      entry.SetValue(nt::Value::MakeStringArray(getter(buf), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsStringArray()) return;
+            SmartDashboard::PostListenerTask(
+                [=] { setter(event.value->GetStringArray()); });
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddSmallRawProperty(
+    const wpi::Twine& key,
+    std::function<wpi::StringRef(wpi::SmallVectorImpl<char>& buf)> getter,
+    std::function<void(wpi::StringRef)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      wpi::SmallVector<char, 128> buf;
+      entry.SetValue(nt::Value::MakeRaw(getter(buf), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsRaw()) return;
+            SmartDashboard::PostListenerTask(
+                [=] { setter(event.value->GetRaw()); });
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp
new file mode 100644
index 0000000..2f7af9c
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/smartdashboard/SendableChooserBase.h"
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+std::atomic_int SendableChooserBase::s_instances{0};
+
+SendableChooserBase::SendableChooserBase() : m_instance{s_instances++} {
+  SendableRegistry::GetInstance().Add(this, "SendableChooser", m_instance);
+}
+
+SendableChooserBase::SendableChooserBase(SendableChooserBase&& oth)
+    : SendableHelper(std::move(oth)),
+      m_defaultChoice(std::move(oth.m_defaultChoice)),
+      m_selected(std::move(oth.m_selected)),
+      m_haveSelected(std::move(oth.m_haveSelected)),
+      m_activeEntries(std::move(oth.m_activeEntries)),
+      m_instance(std::move(oth.m_instance)) {}
+
+SendableChooserBase& SendableChooserBase::operator=(SendableChooserBase&& oth) {
+  SendableHelper::operator=(oth);
+  std::scoped_lock lock(m_mutex, oth.m_mutex);
+  m_defaultChoice = std::move(oth.m_defaultChoice);
+  m_selected = std::move(oth.m_selected);
+  m_haveSelected = std::move(oth.m_haveSelected);
+  m_activeEntries = std::move(oth.m_activeEntries);
+  m_instance = std::move(oth.m_instance);
+  return *this;
+}
diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SendableRegistry.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SendableRegistry.cpp
new file mode 100644
index 0000000..9d57ad6
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/smartdashboard/SendableRegistry.cpp
@@ -0,0 +1,341 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+#include <memory>
+
+#include <wpi/DenseMap.h>
+#include <wpi/SmallVector.h>
+#include <wpi/UidVector.h>
+#include <wpi/mutex.h>
+
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableBuilderImpl.h"
+
+using namespace frc;
+
+struct SendableRegistry::Impl {
+  struct Component {
+    Sendable* sendable = nullptr;
+    SendableBuilderImpl builder;
+    std::string name;
+    std::string subsystem = "Ungrouped";
+    Sendable* parent = nullptr;
+    bool liveWindow = false;
+    wpi::SmallVector<std::shared_ptr<void>, 2> data;
+
+    void SetName(const wpi::Twine& moduleType, int channel) {
+      name =
+          (moduleType + wpi::Twine('[') + wpi::Twine(channel) + wpi::Twine(']'))
+              .str();
+    }
+
+    void SetName(const wpi::Twine& moduleType, int moduleNumber, int channel) {
+      name = (moduleType + wpi::Twine('[') + wpi::Twine(moduleNumber) +
+              wpi::Twine(',') + wpi::Twine(channel) + wpi::Twine(']'))
+                 .str();
+    }
+  };
+
+  wpi::recursive_mutex mutex;
+
+  wpi::UidVector<std::unique_ptr<Component>, 32> components;
+  wpi::DenseMap<void*, UID> componentMap;
+  int nextDataHandle = 0;
+
+  Component& GetOrAdd(void* sendable, UID* uid = nullptr);
+};
+
+SendableRegistry::Impl::Component& SendableRegistry::Impl::GetOrAdd(
+    void* sendable, UID* uid) {
+  UID& compUid = componentMap[sendable];
+  if (compUid == 0)
+    compUid = components.emplace_back(std::make_unique<Component>()) + 1;
+  if (uid) *uid = compUid;
+
+  return *components[compUid - 1];
+}
+
+SendableRegistry& SendableRegistry::GetInstance() {
+  static SendableRegistry instance;
+  return instance;
+}
+
+void SendableRegistry::Add(Sendable* sendable, const wpi::Twine& name) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto& comp = m_impl->GetOrAdd(sendable);
+  comp.sendable = sendable;
+  comp.name = name.str();
+}
+
+void SendableRegistry::Add(Sendable* sendable, const wpi::Twine& moduleType,
+                           int channel) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto& comp = m_impl->GetOrAdd(sendable);
+  comp.sendable = sendable;
+  comp.SetName(moduleType, channel);
+}
+
+void SendableRegistry::Add(Sendable* sendable, const wpi::Twine& moduleType,
+                           int moduleNumber, int channel) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto& comp = m_impl->GetOrAdd(sendable);
+  comp.sendable = sendable;
+  comp.SetName(moduleType, moduleNumber, channel);
+}
+
+void SendableRegistry::Add(Sendable* sendable, const wpi::Twine& subsystem,
+                           const wpi::Twine& name) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto& comp = m_impl->GetOrAdd(sendable);
+  comp.sendable = sendable;
+  comp.name = name.str();
+  comp.subsystem = subsystem.str();
+}
+
+void SendableRegistry::AddLW(Sendable* sendable, const wpi::Twine& name) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto& comp = m_impl->GetOrAdd(sendable);
+  comp.sendable = sendable;
+  comp.liveWindow = true;
+  comp.name = name.str();
+}
+
+void SendableRegistry::AddLW(Sendable* sendable, const wpi::Twine& moduleType,
+                             int channel) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto& comp = m_impl->GetOrAdd(sendable);
+  comp.sendable = sendable;
+  comp.liveWindow = true;
+  comp.SetName(moduleType, channel);
+}
+
+void SendableRegistry::AddLW(Sendable* sendable, const wpi::Twine& moduleType,
+                             int moduleNumber, int channel) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto& comp = m_impl->GetOrAdd(sendable);
+  comp.sendable = sendable;
+  comp.liveWindow = true;
+  comp.SetName(moduleType, moduleNumber, channel);
+}
+
+void SendableRegistry::AddLW(Sendable* sendable, const wpi::Twine& subsystem,
+                             const wpi::Twine& name) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto& comp = m_impl->GetOrAdd(sendable);
+  comp.sendable = sendable;
+  comp.liveWindow = true;
+  comp.name = name.str();
+  comp.subsystem = subsystem.str();
+}
+
+void SendableRegistry::AddChild(Sendable* parent, Sendable* child) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto& comp = m_impl->GetOrAdd(child);
+  comp.parent = parent;
+}
+
+void SendableRegistry::AddChild(Sendable* parent, void* child) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto& comp = m_impl->GetOrAdd(child);
+  comp.parent = parent;
+}
+
+bool SendableRegistry::Remove(Sendable* sendable) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto it = m_impl->componentMap.find(sendable);
+  if (it == m_impl->componentMap.end()) return false;
+  UID compUid = it->getSecond();
+  m_impl->components.erase(compUid - 1);
+  m_impl->componentMap.erase(it);
+  // update any parent pointers
+  for (auto&& comp : m_impl->components) {
+    if (comp->parent == sendable) comp->parent = nullptr;
+  }
+  return true;
+}
+
+void SendableRegistry::Move(Sendable* to, Sendable* from) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto it = m_impl->componentMap.find(from);
+  if (it == m_impl->componentMap.end()) return;
+  UID compUid = it->getSecond();
+  m_impl->componentMap.erase(it);
+  m_impl->componentMap[to] = compUid;
+  auto& comp = *m_impl->components[compUid - 1];
+  comp.sendable = to;
+  if (comp.builder.HasTable()) {
+    // rebuild builder, as lambda captures can point to "from"
+    comp.builder.ClearProperties();
+    to->InitSendable(comp.builder);
+  }
+  // update any parent pointers
+  for (auto&& comp : m_impl->components) {
+    if (comp->parent == from) comp->parent = to;
+  }
+}
+
+bool SendableRegistry::Contains(const Sendable* sendable) const {
+  std::scoped_lock lock(m_impl->mutex);
+  return m_impl->componentMap.count(sendable) != 0;
+}
+
+std::string SendableRegistry::GetName(const Sendable* sendable) const {
+  std::scoped_lock lock(m_impl->mutex);
+  auto it = m_impl->componentMap.find(sendable);
+  if (it == m_impl->componentMap.end()) return std::string{};
+  return m_impl->components[it->getSecond() - 1]->name;
+}
+
+void SendableRegistry::SetName(Sendable* sendable, const wpi::Twine& name) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto it = m_impl->componentMap.find(sendable);
+  if (it == m_impl->componentMap.end()) return;
+  m_impl->components[it->getSecond() - 1]->name = name.str();
+}
+
+void SendableRegistry::SetName(Sendable* sendable, const wpi::Twine& moduleType,
+                               int channel) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto it = m_impl->componentMap.find(sendable);
+  if (it == m_impl->componentMap.end()) return;
+  m_impl->components[it->getSecond() - 1]->SetName(moduleType, channel);
+}
+
+void SendableRegistry::SetName(Sendable* sendable, const wpi::Twine& moduleType,
+                               int moduleNumber, int channel) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto it = m_impl->componentMap.find(sendable);
+  if (it == m_impl->componentMap.end()) return;
+  m_impl->components[it->getSecond() - 1]->SetName(moduleType, moduleNumber,
+                                                   channel);
+}
+
+void SendableRegistry::SetName(Sendable* sendable, const wpi::Twine& subsystem,
+                               const wpi::Twine& name) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto it = m_impl->componentMap.find(sendable);
+  if (it == m_impl->componentMap.end()) return;
+  auto& comp = *m_impl->components[it->getSecond() - 1];
+  comp.name = name.str();
+  comp.subsystem = subsystem.str();
+}
+
+std::string SendableRegistry::GetSubsystem(const Sendable* sendable) const {
+  std::scoped_lock lock(m_impl->mutex);
+  auto it = m_impl->componentMap.find(sendable);
+  if (it == m_impl->componentMap.end()) return std::string{};
+  return m_impl->components[it->getSecond() - 1]->subsystem;
+}
+
+void SendableRegistry::SetSubsystem(Sendable* sendable,
+                                    const wpi::Twine& subsystem) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto it = m_impl->componentMap.find(sendable);
+  if (it == m_impl->componentMap.end()) return;
+  m_impl->components[it->getSecond() - 1]->subsystem = subsystem.str();
+}
+
+int SendableRegistry::GetDataHandle() {
+  std::scoped_lock lock(m_impl->mutex);
+  return m_impl->nextDataHandle++;
+}
+
+std::shared_ptr<void> SendableRegistry::SetData(Sendable* sendable, int handle,
+                                                std::shared_ptr<void> data) {
+  assert(handle >= 0);
+  std::scoped_lock lock(m_impl->mutex);
+  auto it = m_impl->componentMap.find(sendable);
+  if (it == m_impl->componentMap.end()) return nullptr;
+  auto& comp = *m_impl->components[it->getSecond() - 1];
+  std::shared_ptr<void> rv;
+  if (static_cast<size_t>(handle) < comp.data.size())
+    rv = std::move(comp.data[handle]);
+  else
+    comp.data.resize(handle + 1);
+  comp.data[handle] = std::move(data);
+  return rv;
+}
+
+std::shared_ptr<void> SendableRegistry::GetData(Sendable* sendable,
+                                                int handle) {
+  assert(handle >= 0);
+  std::scoped_lock lock(m_impl->mutex);
+  auto it = m_impl->componentMap.find(sendable);
+  if (it == m_impl->componentMap.end()) return nullptr;
+  auto& comp = *m_impl->components[it->getSecond() - 1];
+  if (static_cast<size_t>(handle) >= comp.data.size()) return nullptr;
+  return comp.data[handle];
+}
+
+void SendableRegistry::EnableLiveWindow(Sendable* sendable) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto it = m_impl->componentMap.find(sendable);
+  if (it == m_impl->componentMap.end()) return;
+  m_impl->components[it->getSecond() - 1]->liveWindow = true;
+}
+
+void SendableRegistry::DisableLiveWindow(Sendable* sendable) {
+  std::scoped_lock lock(m_impl->mutex);
+  auto it = m_impl->componentMap.find(sendable);
+  if (it == m_impl->componentMap.end()) return;
+  m_impl->components[it->getSecond() - 1]->liveWindow = false;
+}
+
+SendableRegistry::UID SendableRegistry::GetUniqueId(Sendable* sendable) {
+  std::scoped_lock lock(m_impl->mutex);
+  UID uid;
+  auto& comp = m_impl->GetOrAdd(sendable, &uid);
+  comp.sendable = sendable;
+  return uid;
+}
+
+Sendable* SendableRegistry::GetSendable(UID uid) {
+  if (uid == 0) return nullptr;
+  std::scoped_lock lock(m_impl->mutex);
+  return m_impl->components[uid - 1]->sendable;
+}
+
+void SendableRegistry::Publish(UID sendableUid,
+                               std::shared_ptr<NetworkTable> table) {
+  std::scoped_lock lock(m_impl->mutex);
+  if (sendableUid == 0) return;
+  auto& comp = *m_impl->components[sendableUid - 1];
+  comp.builder = SendableBuilderImpl{};  // clear any current builder
+  comp.builder.SetTable(table);
+  comp.sendable->InitSendable(comp.builder);
+  comp.builder.UpdateTable();
+  comp.builder.StartListeners();
+}
+
+void SendableRegistry::Update(UID sendableUid) {
+  if (sendableUid == 0) return;
+  std::scoped_lock lock(m_impl->mutex);
+  m_impl->components[sendableUid - 1]->builder.UpdateTable();
+}
+
+void SendableRegistry::ForeachLiveWindow(
+    int dataHandle,
+    wpi::function_ref<void(CallbackData& data)> callback) const {
+  assert(dataHandle >= 0);
+  std::scoped_lock lock(m_impl->mutex);
+  wpi::SmallVector<Impl::Component*, 128> components;
+  for (auto&& comp : m_impl->components) components.emplace_back(comp.get());
+  for (auto comp : components) {
+    if (comp->sendable && comp->liveWindow) {
+      if (static_cast<size_t>(dataHandle) >= comp->data.size())
+        comp->data.resize(dataHandle + 1);
+      CallbackData cbdata{comp->sendable,         comp->name,
+                          comp->subsystem,        comp->parent,
+                          comp->data[dataHandle], comp->builder};
+      callback(cbdata);
+    }
+  }
+}
+
+SendableRegistry::SendableRegistry() : m_impl(new Impl) {}
diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp
new file mode 100644
index 0000000..5e70a4c
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp
@@ -0,0 +1,263 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/smartdashboard/SmartDashboard.h"
+
+#include <hal/FRCUsageReporting.h>
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/StringMap.h>
+#include <wpi/mutex.h>
+
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+namespace {
+class Singleton {
+ public:
+  static Singleton& GetInstance();
+
+  std::shared_ptr<nt::NetworkTable> table;
+  wpi::StringMap<SendableRegistry::UID> tablesToData;
+  wpi::mutex tablesToDataMutex;
+
+ private:
+  Singleton() {
+    table = nt::NetworkTableInstance::GetDefault().GetTable("SmartDashboard");
+    HAL_Report(HALUsageReporting::kResourceType_SmartDashboard, 0);
+  }
+  Singleton(const Singleton&) = delete;
+  Singleton& operator=(const Singleton&) = delete;
+};
+
+}  // namespace
+
+Singleton& Singleton::GetInstance() {
+  static Singleton instance;
+  return instance;
+}
+
+void SmartDashboard::init() { Singleton::GetInstance(); }
+
+bool SmartDashboard::ContainsKey(wpi::StringRef key) {
+  return Singleton::GetInstance().table->ContainsKey(key);
+}
+
+std::vector<std::string> SmartDashboard::GetKeys(int types) {
+  return Singleton::GetInstance().table->GetKeys(types);
+}
+
+void SmartDashboard::SetPersistent(wpi::StringRef key) {
+  Singleton::GetInstance().table->GetEntry(key).SetPersistent();
+}
+
+void SmartDashboard::ClearPersistent(wpi::StringRef key) {
+  Singleton::GetInstance().table->GetEntry(key).ClearPersistent();
+}
+
+bool SmartDashboard::IsPersistent(wpi::StringRef key) {
+  return Singleton::GetInstance().table->GetEntry(key).IsPersistent();
+}
+
+void SmartDashboard::SetFlags(wpi::StringRef key, unsigned int flags) {
+  Singleton::GetInstance().table->GetEntry(key).SetFlags(flags);
+}
+
+void SmartDashboard::ClearFlags(wpi::StringRef key, unsigned int flags) {
+  Singleton::GetInstance().table->GetEntry(key).ClearFlags(flags);
+}
+
+unsigned int SmartDashboard::GetFlags(wpi::StringRef key) {
+  return Singleton::GetInstance().table->GetEntry(key).GetFlags();
+}
+
+void SmartDashboard::Delete(wpi::StringRef key) {
+  Singleton::GetInstance().table->Delete(key);
+}
+
+nt::NetworkTableEntry SmartDashboard::GetEntry(wpi::StringRef key) {
+  return Singleton::GetInstance().table->GetEntry(key);
+}
+
+void SmartDashboard::PutData(wpi::StringRef key, Sendable* data) {
+  if (data == nullptr) {
+    wpi_setGlobalWPIErrorWithContext(NullParameter, "value");
+    return;
+  }
+  auto& inst = Singleton::GetInstance();
+  std::scoped_lock lock(inst.tablesToDataMutex);
+  auto& uid = inst.tablesToData[key];
+  auto& registry = SendableRegistry::GetInstance();
+  Sendable* sddata = registry.GetSendable(uid);
+  if (sddata != data) {
+    uid = registry.GetUniqueId(data);
+    auto dataTable = inst.table->GetSubTable(key);
+    registry.Publish(uid, dataTable);
+    dataTable->GetEntry(".name").SetString(key);
+  }
+}
+
+void SmartDashboard::PutData(Sendable* value) {
+  if (value == nullptr) {
+    wpi_setGlobalWPIErrorWithContext(NullParameter, "value");
+    return;
+  }
+  auto name = SendableRegistry::GetInstance().GetName(value);
+  if (!name.empty()) PutData(name, value);
+}
+
+Sendable* SmartDashboard::GetData(wpi::StringRef key) {
+  auto& inst = Singleton::GetInstance();
+  std::scoped_lock lock(inst.tablesToDataMutex);
+  auto it = inst.tablesToData.find(key);
+  if (it == inst.tablesToData.end()) {
+    wpi_setGlobalWPIErrorWithContext(SmartDashboardMissingKey, key);
+    return nullptr;
+  }
+  return SendableRegistry::GetInstance().GetSendable(it->getValue());
+}
+
+bool SmartDashboard::PutBoolean(wpi::StringRef keyName, bool value) {
+  return Singleton::GetInstance().table->GetEntry(keyName).SetBoolean(value);
+}
+
+bool SmartDashboard::SetDefaultBoolean(wpi::StringRef key, bool defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultBoolean(
+      defaultValue);
+}
+
+bool SmartDashboard::GetBoolean(wpi::StringRef keyName, bool defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(keyName).GetBoolean(
+      defaultValue);
+}
+
+bool SmartDashboard::PutNumber(wpi::StringRef keyName, double value) {
+  return Singleton::GetInstance().table->GetEntry(keyName).SetDouble(value);
+}
+
+bool SmartDashboard::SetDefaultNumber(wpi::StringRef key, double defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultDouble(
+      defaultValue);
+}
+
+double SmartDashboard::GetNumber(wpi::StringRef keyName, double defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(keyName).GetDouble(
+      defaultValue);
+}
+
+bool SmartDashboard::PutString(wpi::StringRef keyName, wpi::StringRef value) {
+  return Singleton::GetInstance().table->GetEntry(keyName).SetString(value);
+}
+
+bool SmartDashboard::SetDefaultString(wpi::StringRef key,
+                                      wpi::StringRef defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultString(
+      defaultValue);
+}
+
+std::string SmartDashboard::GetString(wpi::StringRef keyName,
+                                      wpi::StringRef defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(keyName).GetString(
+      defaultValue);
+}
+
+bool SmartDashboard::PutBooleanArray(wpi::StringRef key,
+                                     wpi::ArrayRef<int> value) {
+  return Singleton::GetInstance().table->GetEntry(key).SetBooleanArray(value);
+}
+
+bool SmartDashboard::SetDefaultBooleanArray(wpi::StringRef key,
+                                            wpi::ArrayRef<int> defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultBooleanArray(
+      defaultValue);
+}
+
+std::vector<int> SmartDashboard::GetBooleanArray(
+    wpi::StringRef key, wpi::ArrayRef<int> defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).GetBooleanArray(
+      defaultValue);
+}
+
+bool SmartDashboard::PutNumberArray(wpi::StringRef key,
+                                    wpi::ArrayRef<double> value) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDoubleArray(value);
+}
+
+bool SmartDashboard::SetDefaultNumberArray(wpi::StringRef key,
+                                           wpi::ArrayRef<double> defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultDoubleArray(
+      defaultValue);
+}
+
+std::vector<double> SmartDashboard::GetNumberArray(
+    wpi::StringRef key, wpi::ArrayRef<double> defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).GetDoubleArray(
+      defaultValue);
+}
+
+bool SmartDashboard::PutStringArray(wpi::StringRef key,
+                                    wpi::ArrayRef<std::string> value) {
+  return Singleton::GetInstance().table->GetEntry(key).SetStringArray(value);
+}
+
+bool SmartDashboard::SetDefaultStringArray(
+    wpi::StringRef key, wpi::ArrayRef<std::string> defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultStringArray(
+      defaultValue);
+}
+
+std::vector<std::string> SmartDashboard::GetStringArray(
+    wpi::StringRef key, wpi::ArrayRef<std::string> defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).GetStringArray(
+      defaultValue);
+}
+
+bool SmartDashboard::PutRaw(wpi::StringRef key, wpi::StringRef value) {
+  return Singleton::GetInstance().table->GetEntry(key).SetRaw(value);
+}
+
+bool SmartDashboard::SetDefaultRaw(wpi::StringRef key,
+                                   wpi::StringRef defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultRaw(
+      defaultValue);
+}
+
+std::string SmartDashboard::GetRaw(wpi::StringRef key,
+                                   wpi::StringRef defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).GetRaw(defaultValue);
+}
+
+bool SmartDashboard::PutValue(wpi::StringRef keyName,
+                              std::shared_ptr<nt::Value> value) {
+  return Singleton::GetInstance().table->GetEntry(keyName).SetValue(value);
+}
+
+bool SmartDashboard::SetDefaultValue(wpi::StringRef key,
+                                     std::shared_ptr<nt::Value> defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultValue(
+      defaultValue);
+}
+
+std::shared_ptr<nt::Value> SmartDashboard::GetValue(wpi::StringRef keyName) {
+  return Singleton::GetInstance().table->GetEntry(keyName).GetValue();
+}
+
+detail::ListenerExecutor SmartDashboard::listenerExecutor;
+
+void SmartDashboard::PostListenerTask(std::function<void()> task) {
+  listenerExecutor.Execute(task);
+}
+
+void SmartDashboard::UpdateValues() {
+  auto& registry = SendableRegistry::GetInstance();
+  auto& inst = Singleton::GetInstance();
+  std::scoped_lock lock(inst.tablesToDataMutex);
+  for (auto& i : inst.tablesToData) registry.Update(i.getValue());
+  listenerExecutor.RunListenerTasks();
+}
diff --git a/wpilibc/src/main/native/cpp/spline/CubicHermiteSpline.cpp b/wpilibc/src/main/native/cpp/spline/CubicHermiteSpline.cpp
new file mode 100644
index 0000000..3991fec
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/spline/CubicHermiteSpline.cpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/spline/CubicHermiteSpline.h"
+
+using namespace frc;
+
+CubicHermiteSpline::CubicHermiteSpline(
+    std::array<double, 2> xInitialControlVector,
+    std::array<double, 2> xFinalControlVector,
+    std::array<double, 2> yInitialControlVector,
+    std::array<double, 2> yFinalControlVector) {
+  const auto hermite = MakeHermiteBasis();
+  const auto x =
+      ControlVectorFromArrays(xInitialControlVector, xFinalControlVector);
+  const auto y =
+      ControlVectorFromArrays(yInitialControlVector, yFinalControlVector);
+
+  // Populate first two rows with coefficients.
+  m_coefficients.template block<1, 4>(0, 0) = hermite * x;
+  m_coefficients.template block<1, 4>(1, 0) = hermite * y;
+
+  // Populate Row 2 and Row 3 with the derivatives of the equations above.
+  // Then populate row 4 and 5 with the second derivatives.
+  for (int i = 0; i < 4; i++) {
+    // Here, we are multiplying by (3 - i) to manually take the derivative. The
+    // power of the term in index 0 is 3, index 1 is 2 and so on. To find the
+    // coefficient of the derivative, we can use the power rule and multiply
+    // the existing coefficient by its power.
+    m_coefficients.template block<2, 1>(2, i) =
+        m_coefficients.template block<2, 1>(0, i) * (3 - i);
+  }
+
+  for (int i = 0; i < 3; i++) {
+    // Here, we are multiplying by (2 - i) to manually take the derivative. The
+    // power of the term in index 0 is 2, index 1 is 1 and so on. To find the
+    // coefficient of the derivative, we can use the power rule and multiply
+    // the existing coefficient by its power.
+    m_coefficients.template block<2, 1>(4, i) =
+        m_coefficients.template block<2, 1>(2, i) * (2 - i);
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/spline/QuinticHermiteSpline.cpp b/wpilibc/src/main/native/cpp/spline/QuinticHermiteSpline.cpp
new file mode 100644
index 0000000..bb8ad3c
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/spline/QuinticHermiteSpline.cpp
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/spline/QuinticHermiteSpline.h"
+
+using namespace frc;
+
+QuinticHermiteSpline::QuinticHermiteSpline(
+    std::array<double, 3> xInitialControlVector,
+    std::array<double, 3> xFinalControlVector,
+    std::array<double, 3> yInitialControlVector,
+    std::array<double, 3> yFinalControlVector) {
+  const auto hermite = MakeHermiteBasis();
+  const auto x =
+      ControlVectorFromArrays(xInitialControlVector, xFinalControlVector);
+  const auto y =
+      ControlVectorFromArrays(yInitialControlVector, yFinalControlVector);
+
+  // Populate first two rows with coefficients.
+  m_coefficients.template block<1, 6>(0, 0) = (hermite * x).transpose();
+  m_coefficients.template block<1, 6>(1, 0) = (hermite * y).transpose();
+
+  // Populate Row 2 and Row 3 with the derivatives of the equations above.
+  // Then populate row 4 and 5 with the second derivatives.
+  for (int i = 0; i < 6; i++) {
+    // Here, we are multiplying by (5 - i) to manually take the derivative. The
+    // power of the term in index 0 is 5, index 1 is 4 and so on. To find the
+    // coefficient of the derivative, we can use the power rule and multiply
+    // the existing coefficient by its power.
+    m_coefficients.template block<2, 1>(2, i) =
+        m_coefficients.template block<2, 1>(0, i) * (5 - i);
+  }
+  for (int i = 0; i < 5; i++) {
+    // Here, we are multiplying by (4 - i) to manually take the derivative. The
+    // power of the term in index 0 is 4, index 1 is 3 and so on. To find the
+    // coefficient of the derivative, we can use the power rule and multiply
+    // the existing coefficient by its power.
+    m_coefficients.template block<2, 1>(4, i) =
+        m_coefficients.template block<2, 1>(2, i) * (4 - i);
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/spline/SplineHelper.cpp b/wpilibc/src/main/native/cpp/spline/SplineHelper.cpp
new file mode 100644
index 0000000..cbfc8c1
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/spline/SplineHelper.cpp
@@ -0,0 +1,208 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/spline/SplineHelper.h"
+
+#include <cstddef>
+
+using namespace frc;
+
+std::vector<CubicHermiteSpline> SplineHelper::CubicSplinesFromControlVectors(
+    const Spline<3>::ControlVector& start, std::vector<Translation2d> waypoints,
+    const Spline<3>::ControlVector& end) {
+  std::vector<CubicHermiteSpline> splines;
+
+  std::array<double, 2> xInitial = start.x;
+  std::array<double, 2> yInitial = start.y;
+  std::array<double, 2> xFinal = end.x;
+  std::array<double, 2> yFinal = end.y;
+
+  if (waypoints.size() > 1) {
+    waypoints.emplace(waypoints.begin(),
+                      Translation2d{units::meter_t(xInitial[0]),
+                                    units::meter_t(yInitial[0])});
+    waypoints.emplace_back(
+        Translation2d{units::meter_t(xFinal[0]), units::meter_t(yFinal[0])});
+
+    // Populate tridiagonal system for clamped cubic
+    /* See:
+    https://www.uio.no/studier/emner/matnat/ifi/nedlagte-emner/INF-MAT4350/h08
+    /undervisningsmateriale/chap7alecture.pdf
+    */
+
+    // Above-diagonal of tridiagonal matrix, zero-padded
+    std::vector<double> a;
+    // Diagonal of tridiagonal matrix
+    std::vector<double> b(waypoints.size() - 2, 4.0);
+    // Below-diagonal of tridiagonal matrix, zero-padded
+    std::vector<double> c;
+    // rhs vectors
+    std::vector<double> dx, dy;
+    // solution vectors
+    std::vector<double> fx(waypoints.size() - 2, 0.0),
+        fy(waypoints.size() - 2, 0.0);
+
+    // populate above-diagonal and below-diagonal vectors
+    a.emplace_back(0);
+    for (size_t i = 0; i < waypoints.size() - 3; ++i) {
+      a.emplace_back(1);
+      c.emplace_back(1);
+    }
+    c.emplace_back(0);
+
+    // populate rhs vectors
+    dx.emplace_back(
+        3 * (waypoints[2].X().to<double>() - waypoints[0].X().to<double>()) -
+        xInitial[1]);
+    dy.emplace_back(
+        3 * (waypoints[2].Y().to<double>() - waypoints[0].Y().to<double>()) -
+        yInitial[1]);
+    if (waypoints.size() > 4) {
+      for (size_t i = 1; i <= waypoints.size() - 4; ++i) {
+        dx.emplace_back(3 * (waypoints[i + 1].X().to<double>() -
+                             waypoints[i - 1].X().to<double>()));
+        dy.emplace_back(3 * (waypoints[i + 1].Y().to<double>() -
+                             waypoints[i - 1].Y().to<double>()));
+      }
+    }
+    dx.emplace_back(3 * (waypoints[waypoints.size() - 1].X().to<double>() -
+                         waypoints[waypoints.size() - 3].X().to<double>()) -
+                    xFinal[1]);
+    dy.emplace_back(3 * (waypoints[waypoints.size() - 1].Y().to<double>() -
+                         waypoints[waypoints.size() - 3].Y().to<double>()) -
+                    yFinal[1]);
+
+    // Compute solution to tridiagonal system
+    ThomasAlgorithm(a, b, c, dx, &fx);
+    ThomasAlgorithm(a, b, c, dy, &fy);
+
+    fx.emplace(fx.begin(), xInitial[1]);
+    fx.emplace_back(xFinal[1]);
+    fy.emplace(fy.begin(), yInitial[1]);
+    fy.emplace_back(yFinal[1]);
+
+    for (size_t i = 0; i < fx.size() - 1; ++i) {
+      // Create the spline.
+      const CubicHermiteSpline spline{
+          {waypoints[i].X().to<double>(), fx[i]},
+          {waypoints[i + 1].X().to<double>(), fx[i + 1]},
+          {waypoints[i].Y().to<double>(), fy[i]},
+          {waypoints[i + 1].Y().to<double>(), fy[i + 1]}};
+
+      splines.push_back(spline);
+    }
+  } else if (waypoints.size() == 1) {
+    const double xDeriv =
+        (3 * (xFinal[0] - xInitial[0]) - xFinal[1] - xInitial[1]) / 4.0;
+    const double yDeriv =
+        (3 * (yFinal[0] - yInitial[0]) - yFinal[1] - yInitial[1]) / 4.0;
+
+    std::array<double, 2> midXControlVector{waypoints[0].X().to<double>(),
+                                            xDeriv};
+    std::array<double, 2> midYControlVector{waypoints[0].Y().to<double>(),
+                                            yDeriv};
+
+    splines.emplace_back(xInitial, midXControlVector, yInitial,
+                         midYControlVector);
+    splines.emplace_back(midXControlVector, xFinal, midYControlVector, yFinal);
+
+  } else {
+    // Create the spline.
+    const CubicHermiteSpline spline{xInitial, xFinal, yInitial, yFinal};
+    splines.push_back(spline);
+  }
+
+  return splines;
+}
+
+std::vector<QuinticHermiteSpline>
+SplineHelper::QuinticSplinesFromControlVectors(
+    const std::vector<Spline<5>::ControlVector>& controlVectors) {
+  std::vector<QuinticHermiteSpline> splines;
+  for (size_t i = 0; i < controlVectors.size() - 1; ++i) {
+    auto& xInitial = controlVectors[i].x;
+    auto& yInitial = controlVectors[i].y;
+    auto& xFinal = controlVectors[i + 1].x;
+    auto& yFinal = controlVectors[i + 1].y;
+    splines.emplace_back(xInitial, xFinal, yInitial, yFinal);
+  }
+  return splines;
+}
+
+std::array<Spline<3>::ControlVector, 2>
+SplineHelper::CubicControlVectorsFromWaypoints(
+    const Pose2d& start, const std::vector<Translation2d>& interiorWaypoints,
+    const Pose2d& end) {
+  double scalar;
+  if (interiorWaypoints.empty()) {
+    scalar = 1.2 * start.Translation().Distance(end.Translation()).to<double>();
+  } else {
+    scalar =
+        1.2 *
+        start.Translation().Distance(interiorWaypoints.front()).to<double>();
+  }
+  const auto initialCV = CubicControlVector(scalar, start);
+  if (!interiorWaypoints.empty()) {
+    scalar =
+        1.2 * end.Translation().Distance(interiorWaypoints.back()).to<double>();
+  }
+  const auto finalCV = CubicControlVector(scalar, end);
+  return {initialCV, finalCV};
+}
+
+std::vector<Spline<5>::ControlVector>
+SplineHelper::QuinticControlVectorsFromWaypoints(
+    const std::vector<Pose2d>& waypoints) {
+  std::vector<Spline<5>::ControlVector> vectors;
+  for (size_t i = 0; i < waypoints.size() - 1; ++i) {
+    auto& p0 = waypoints[i];
+    auto& p1 = waypoints[i + 1];
+
+    // This just makes the splines look better.
+    const auto scalar =
+        1.2 * p0.Translation().Distance(p1.Translation()).to<double>();
+
+    vectors.push_back(QuinticControlVector(scalar, p0));
+    vectors.push_back(QuinticControlVector(scalar, p1));
+  }
+  return vectors;
+}
+
+void SplineHelper::ThomasAlgorithm(const std::vector<double>& a,
+                                   const std::vector<double>& b,
+                                   const std::vector<double>& c,
+                                   const std::vector<double>& d,
+                                   std::vector<double>* solutionVector) {
+  auto& f = *solutionVector;
+  size_t N = d.size();
+
+  // Create the temporary vectors
+  // Note that this is inefficient as it is possible to call
+  // this function many times. A better implementation would
+  // pass these temporary matrices by non-const reference to
+  // save excess allocation and deallocation
+  std::vector<double> c_star(N, 0.0);
+  std::vector<double> d_star(N, 0.0);
+
+  // This updates the coefficients in the first row
+  // Note that we should be checking for division by zero here
+  c_star[0] = c[0] / b[0];
+  d_star[0] = d[0] / b[0];
+
+  // Create the c_star and d_star coefficients in the forward sweep
+  for (size_t i = 1; i < N; ++i) {
+    double m = 1.0 / (b[i] - a[i] * c_star[i - 1]);
+    c_star[i] = c[i] * m;
+    d_star[i] = (d[i] - a[i] * d_star[i - 1]) * m;
+  }
+
+  f[N - 1] = d_star[N - 1];
+  // This is the reverse sweep, used to update the solution vector f
+  for (int i = N - 2; i >= 0; i--) {
+    f[i] = d_star[i] - c_star[i] * f[i + 1];
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/spline/SplineParameterizer.cpp b/wpilibc/src/main/native/cpp/spline/SplineParameterizer.cpp
new file mode 100644
index 0000000..f3c42c6
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/spline/SplineParameterizer.cpp
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/spline/SplineParameterizer.h"
+
+constexpr units::meter_t frc::SplineParameterizer::kMaxDx;
+constexpr units::meter_t frc::SplineParameterizer::kMaxDy;
+constexpr units::radian_t frc::SplineParameterizer::kMaxDtheta;
diff --git a/wpilibc/src/main/native/cpp/trajectory/Trajectory.cpp b/wpilibc/src/main/native/cpp/trajectory/Trajectory.cpp
new file mode 100644
index 0000000..84d4f37
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/trajectory/Trajectory.cpp
@@ -0,0 +1,153 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/trajectory/Trajectory.h"
+
+#include <wpi/json.h>
+
+using namespace frc;
+
+bool Trajectory::State::operator==(const Trajectory::State& other) const {
+  return t == other.t && velocity == other.velocity &&
+         acceleration == other.acceleration && pose == other.pose &&
+         curvature == other.curvature;
+}
+
+bool Trajectory::State::operator!=(const Trajectory::State& other) const {
+  return !operator==(other);
+}
+
+Trajectory::State Trajectory::State::Interpolate(State endValue,
+                                                 double i) const {
+  // Find the new [t] value.
+  const auto newT = Lerp(t, endValue.t, i);
+
+  // Find the delta time between the current state and the interpolated state.
+  const auto deltaT = newT - t;
+
+  // If delta time is negative, flip the order of interpolation.
+  if (deltaT < 0_s) return endValue.Interpolate(*this, 1.0 - i);
+
+  // Check whether the robot is reversing at this stage.
+  const auto reversing =
+      velocity < 0_mps ||
+      (units::math::abs(velocity) < 1E-9_mps && acceleration < 0_mps_sq);
+
+  // Calculate the new velocity.
+  // v = v_0 + at
+  const units::meters_per_second_t newV = velocity + (acceleration * deltaT);
+
+  // Calculate the change in position.
+  // delta_s = v_0 t + 0.5 at^2
+  const units::meter_t newS =
+      (velocity * deltaT + 0.5 * acceleration * deltaT * deltaT) *
+      (reversing ? -1.0 : 1.0);
+
+  // Return the new state. To find the new position for the new state, we need
+  // to interpolate between the two endpoint poses. The fraction for
+  // interpolation is the change in position (delta s) divided by the total
+  // distance between the two endpoints.
+  const double interpolationFrac =
+      newS / endValue.pose.Translation().Distance(pose.Translation());
+
+  return {newT, newV, acceleration,
+          Lerp(pose, endValue.pose, interpolationFrac),
+          Lerp(curvature, endValue.curvature, interpolationFrac)};
+}
+
+Trajectory::Trajectory(const std::vector<State>& states) : m_states(states) {
+  m_totalTime = states.back().t;
+}
+
+Trajectory::State Trajectory::Sample(units::second_t t) const {
+  if (t <= m_states.front().t) return m_states.front();
+  if (t >= m_totalTime) return m_states.back();
+
+  // To get the element that we want, we will use a binary search algorithm
+  // instead of iterating over a for-loop. A binary search is O(std::log(n))
+  // whereas searching using a loop is O(n).
+
+  // This starts at 1 because we use the previous state later on for
+  // interpolation.
+  int low = 1;
+  int high = m_states.size() - 1;
+
+  while (low != high) {
+    int mid = (low + high) / 2;
+    if (m_states[mid].t < t) {
+      // This index and everything under it are less than the requested
+      // timestamp. Therefore, we can discard them.
+      low = mid + 1;
+    } else {
+      // t is at least as large as the element at this index. This means that
+      // anything after it cannot be what we are looking for.
+      high = mid;
+    }
+  }
+
+  // High and Low should be the same.
+
+  // The sample's timestamp is now greater than or equal to the requested
+  // timestamp. If it is greater, we need to interpolate between the
+  // previous state and the current state to get the exact state that we
+  // want.
+  const auto sample = m_states[low];
+  const auto prevSample = m_states[low - 1];
+
+  // If the difference in states is negligible, then we are spot on!
+  if (units::math::abs(sample.t - prevSample.t) < 1E-9_s) {
+    return sample;
+  }
+  // Interpolate between the two states for the state that we want.
+  return prevSample.Interpolate(sample,
+                                (t - prevSample.t) / (sample.t - prevSample.t));
+}
+
+Trajectory Trajectory::TransformBy(const Transform2d& transform) {
+  auto& firstState = m_states[0];
+  auto& firstPose = firstState.pose;
+
+  // Calculate the transformed first pose.
+  auto newFirstPose = firstPose + transform;
+  auto newStates = m_states;
+  newStates[0].pose = newFirstPose;
+
+  for (unsigned int i = 1; i < newStates.size(); i++) {
+    auto& state = newStates[i];
+    // We are transforming relative to the coordinate frame of the new initial
+    // pose.
+    state.pose = newFirstPose + (state.pose - firstPose);
+  }
+
+  return Trajectory(newStates);
+}
+
+Trajectory Trajectory::RelativeTo(const Pose2d& pose) {
+  auto newStates = m_states;
+  for (auto& state : newStates) {
+    state.pose = state.pose.RelativeTo(pose);
+  }
+  return Trajectory(newStates);
+}
+
+void frc::to_json(wpi::json& json, const Trajectory::State& state) {
+  json = wpi::json{{"time", state.t.to<double>()},
+                   {"velocity", state.velocity.to<double>()},
+                   {"acceleration", state.acceleration.to<double>()},
+                   {"pose", state.pose},
+                   {"curvature", state.curvature.to<double>()}};
+}
+
+void frc::from_json(const wpi::json& json, Trajectory::State& state) {
+  state.pose = json.at("pose").get<Pose2d>();
+  state.t = units::second_t{json.at("time").get<double>()};
+  state.velocity =
+      units::meters_per_second_t{json.at("velocity").get<double>()};
+  state.acceleration =
+      units::meters_per_second_squared_t{json.at("acceleration").get<double>()};
+  state.curvature = frc::curvature_t{json.at("curvature").get<double>()};
+}
diff --git a/wpilibc/src/main/native/cpp/trajectory/TrajectoryGenerator.cpp b/wpilibc/src/main/native/cpp/trajectory/TrajectoryGenerator.cpp
new file mode 100644
index 0000000..3c95472
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/trajectory/TrajectoryGenerator.cpp
@@ -0,0 +1,109 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019-2020 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/trajectory/TrajectoryGenerator.h"
+
+#include <utility>
+
+#include "frc/DriverStation.h"
+#include "frc/spline/SplineHelper.h"
+#include "frc/spline/SplineParameterizer.h"
+#include "frc/trajectory/TrajectoryParameterizer.h"
+
+using namespace frc;
+
+const Trajectory TrajectoryGenerator::kDoNothingTrajectory(
+    std::vector<Trajectory::State>{Trajectory::State()});
+
+Trajectory TrajectoryGenerator::GenerateTrajectory(
+    Spline<3>::ControlVector initial,
+    const std::vector<Translation2d>& interiorWaypoints,
+    Spline<3>::ControlVector end, const TrajectoryConfig& config) {
+  const Transform2d flip{Translation2d(), Rotation2d(180_deg)};
+
+  // Make theta normal for trajectory generation if path is reversed.
+  // Flip the headings.
+  if (config.IsReversed()) {
+    initial.x[1] *= -1;
+    initial.y[1] *= -1;
+    end.x[1] *= -1;
+    end.y[1] *= -1;
+  }
+
+  std::vector<frc::SplineParameterizer::PoseWithCurvature> points;
+  try {
+    points =
+        SplinePointsFromSplines(SplineHelper::CubicSplinesFromControlVectors(
+            initial, interiorWaypoints, end));
+  } catch (SplineParameterizer::MalformedSplineException& e) {
+    DriverStation::ReportError(e.what());
+    return kDoNothingTrajectory;
+  }
+
+  // After trajectory generation, flip theta back so it's relative to the
+  // field. Also fix curvature.
+  if (config.IsReversed()) {
+    for (auto& point : points) {
+      point = {point.first + flip, -point.second};
+    }
+  }
+
+  return TrajectoryParameterizer::TimeParameterizeTrajectory(
+      points, config.Constraints(), config.StartVelocity(),
+      config.EndVelocity(), config.MaxVelocity(), config.MaxAcceleration(),
+      config.IsReversed());
+}
+
+Trajectory TrajectoryGenerator::GenerateTrajectory(
+    const Pose2d& start, const std::vector<Translation2d>& interiorWaypoints,
+    const Pose2d& end, const TrajectoryConfig& config) {
+  auto [startCV, endCV] = SplineHelper::CubicControlVectorsFromWaypoints(
+      start, interiorWaypoints, end);
+  return GenerateTrajectory(startCV, interiorWaypoints, endCV, config);
+}
+
+Trajectory TrajectoryGenerator::GenerateTrajectory(
+    std::vector<Spline<5>::ControlVector> controlVectors,
+    const TrajectoryConfig& config) {
+  const Transform2d flip{Translation2d(), Rotation2d(180_deg)};
+  // Make theta normal for trajectory generation if path is reversed.
+  if (config.IsReversed()) {
+    for (auto& vector : controlVectors) {
+      // Flip the headings.
+      vector.x[1] *= -1;
+      vector.y[1] *= -1;
+    }
+  }
+
+  std::vector<frc::SplineParameterizer::PoseWithCurvature> points;
+  try {
+    points = SplinePointsFromSplines(
+        SplineHelper::QuinticSplinesFromControlVectors(controlVectors));
+  } catch (SplineParameterizer::MalformedSplineException& e) {
+    DriverStation::ReportError(e.what());
+    return kDoNothingTrajectory;
+  }
+
+  // After trajectory generation, flip theta back so it's relative to the
+  // field. Also fix curvature.
+  if (config.IsReversed()) {
+    for (auto& point : points) {
+      point = {point.first + flip, -point.second};
+    }
+  }
+
+  return TrajectoryParameterizer::TimeParameterizeTrajectory(
+      points, config.Constraints(), config.StartVelocity(),
+      config.EndVelocity(), config.MaxVelocity(), config.MaxAcceleration(),
+      config.IsReversed());
+}
+
+Trajectory TrajectoryGenerator::GenerateTrajectory(
+    const std::vector<Pose2d>& waypoints, const TrajectoryConfig& config) {
+  return GenerateTrajectory(
+      SplineHelper::QuinticControlVectorsFromWaypoints(waypoints), config);
+}
diff --git a/wpilibc/src/main/native/cpp/trajectory/TrajectoryParameterizer.cpp b/wpilibc/src/main/native/cpp/trajectory/TrajectoryParameterizer.cpp
new file mode 100644
index 0000000..131ae8a
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/trajectory/TrajectoryParameterizer.cpp
@@ -0,0 +1,224 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/*
+ * MIT License
+ *
+ * Copyright (c) 2018 Team 254
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ */
+
+#include "frc/trajectory/TrajectoryParameterizer.h"
+
+using namespace frc;
+
+Trajectory TrajectoryParameterizer::TimeParameterizeTrajectory(
+    const std::vector<PoseWithCurvature>& points,
+    const std::vector<std::unique_ptr<TrajectoryConstraint>>& constraints,
+    units::meters_per_second_t startVelocity,
+    units::meters_per_second_t endVelocity,
+    units::meters_per_second_t maxVelocity,
+    units::meters_per_second_squared_t maxAcceleration, bool reversed) {
+  std::vector<ConstrainedState> constrainedStates(points.size());
+
+  ConstrainedState predecessor{points.front(), 0_m, startVelocity,
+                               -maxAcceleration, maxAcceleration};
+
+  constrainedStates[0] = predecessor;
+
+  // Forward pass
+  for (unsigned int i = 0; i < points.size(); i++) {
+    auto& constrainedState = constrainedStates[i];
+    constrainedState.pose = points[i];
+
+    // Begin constraining based on predecessor
+    units::meter_t ds = constrainedState.pose.first.Translation().Distance(
+        predecessor.pose.first.Translation());
+    constrainedState.distance = ds + predecessor.distance;
+
+    // We may need to iterate to find the maximum end velocity and common
+    // acceleration, since acceleration limits may be a function of velocity.
+    while (true) {
+      // Enforce global max velocity and max reachable velocity by global
+      // acceleration limit. vf = std::sqrt(vi^2 + 2*a*d).
+
+      constrainedState.maxVelocity = units::math::min(
+          maxVelocity,
+          units::math::sqrt(predecessor.maxVelocity * predecessor.maxVelocity +
+                            predecessor.maxAcceleration * ds * 2.0));
+
+      constrainedState.minAcceleration = -maxAcceleration;
+      constrainedState.maxAcceleration = maxAcceleration;
+
+      // At this point, the constrained state is fully constructed apart from
+      // all the custom-defined user constraints.
+      for (const auto& constraint : constraints) {
+        constrainedState.maxVelocity = units::math::min(
+            constrainedState.maxVelocity,
+            constraint->MaxVelocity(constrainedState.pose.first,
+                                    constrainedState.pose.second,
+                                    constrainedState.maxVelocity));
+      }
+
+      // Now enforce all acceleration limits.
+      EnforceAccelerationLimits(reversed, constraints, &constrainedState);
+
+      if (ds.to<double>() < kEpsilon) break;
+
+      // If the actual acceleration for this state is higher than the max
+      // acceleration that we applied, then we need to reduce the max
+      // acceleration of the predecessor and try again.
+      units::meters_per_second_squared_t actualAcceleration =
+          (constrainedState.maxVelocity * constrainedState.maxVelocity -
+           predecessor.maxVelocity * predecessor.maxVelocity) /
+          (ds * 2.0);
+
+      // If we violate the max acceleration constraint, let's modify the
+      // predecessor.
+      if (constrainedState.maxAcceleration < actualAcceleration - 1E-6_mps_sq) {
+        predecessor.maxAcceleration = constrainedState.maxAcceleration;
+      } else {
+        // Constrain the predecessor's max acceleration to the current
+        // acceleration.
+        if (actualAcceleration > predecessor.minAcceleration + 1E-6_mps_sq) {
+          predecessor.maxAcceleration = actualAcceleration;
+        }
+        // If the actual acceleration is less than the predecessor's min
+        // acceleration, it will be repaired in the backward pass.
+        break;
+      }
+    }
+    predecessor = constrainedState;
+  }
+
+  ConstrainedState successor{points.back(), constrainedStates.back().distance,
+                             endVelocity, -maxAcceleration, maxAcceleration};
+
+  // Backward pass
+  for (int i = points.size() - 1; i >= 0; i--) {
+    auto& constrainedState = constrainedStates[i];
+    units::meter_t ds =
+        constrainedState.distance - successor.distance;  // negative
+
+    while (true) {
+      // Enforce max velocity limit (reverse)
+      // vf = std::sqrt(vi^2 + 2*a*d), where vi = successor.
+      units::meters_per_second_t newMaxVelocity =
+          units::math::sqrt(successor.maxVelocity * successor.maxVelocity +
+                            successor.minAcceleration * ds * 2.0);
+
+      // No more limits to impose! This state can be finalized.
+      if (newMaxVelocity >= constrainedState.maxVelocity) break;
+
+      constrainedState.maxVelocity = newMaxVelocity;
+
+      // Check all acceleration constraints with the new max velocity.
+      EnforceAccelerationLimits(reversed, constraints, &constrainedState);
+
+      if (ds.to<double>() > -kEpsilon) break;
+
+      // If the actual acceleration for this state is lower than the min
+      // acceleration, then we need to lower the min acceleration of the
+      // successor and try again.
+      units::meters_per_second_squared_t actualAcceleration =
+          (constrainedState.maxVelocity * constrainedState.maxVelocity -
+           successor.maxVelocity * successor.maxVelocity) /
+          (ds * 2.0);
+      if (constrainedState.minAcceleration > actualAcceleration + 1E-6_mps_sq) {
+        successor.minAcceleration = constrainedState.minAcceleration;
+      } else {
+        successor.minAcceleration = actualAcceleration;
+        break;
+      }
+    }
+    successor = constrainedState;
+  }
+
+  // Now we can integrate the constrained states forward in time to obtain our
+  // trajectory states.
+
+  std::vector<Trajectory::State> states(points.size());
+  units::second_t t = 0_s;
+  units::meter_t s = 0_m;
+  units::meters_per_second_t v = 0_mps;
+
+  for (unsigned int i = 0; i < constrainedStates.size(); i++) {
+    auto state = constrainedStates[i];
+
+    // Calculate the change in position between the current state and the
+    // previous state.
+    units::meter_t ds = state.distance - s;
+
+    // Calculate the acceleration between the current state and the previous
+    // state.
+    units::meters_per_second_squared_t accel =
+        (state.maxVelocity * state.maxVelocity - v * v) / (ds * 2);
+
+    // Calculate dt.
+    units::second_t dt = 0_s;
+    if (i > 0) {
+      states.at(i - 1).acceleration = reversed ? -accel : accel;
+      if (units::math::abs(accel) > 1E-6_mps_sq) {
+        // v_f = v_0 + a * t
+        dt = (state.maxVelocity - v) / accel;
+      } else if (units::math::abs(v) > 1E-6_mps) {
+        // delta_x = v * t
+        dt = ds / v;
+      } else {
+        throw std::runtime_error(
+            "Something went wrong during trajectory generation.");
+      }
+    }
+
+    v = state.maxVelocity;
+    s = state.distance;
+
+    t += dt;
+
+    states[i] = {t, reversed ? -v : v, reversed ? -accel : accel,
+                 state.pose.first, state.pose.second};
+  }
+
+  return Trajectory(states);
+}
+
+void TrajectoryParameterizer::EnforceAccelerationLimits(
+    bool reverse,
+    const std::vector<std::unique_ptr<TrajectoryConstraint>>& constraints,
+    ConstrainedState* state) {
+  for (auto&& constraint : constraints) {
+    double factor = reverse ? -1.0 : 1.0;
+
+    auto minMaxAccel = constraint->MinMaxAcceleration(
+        state->pose.first, state->pose.second, state->maxVelocity * factor);
+
+    state->minAcceleration = units::math::max(
+        state->minAcceleration,
+        reverse ? -minMaxAccel.maxAcceleration : minMaxAccel.minAcceleration);
+
+    state->maxAcceleration = units::math::min(
+        state->maxAcceleration,
+        reverse ? -minMaxAccel.minAcceleration : minMaxAccel.maxAcceleration);
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/trajectory/TrajectoryUtil.cpp b/wpilibc/src/main/native/cpp/trajectory/TrajectoryUtil.cpp
new file mode 100644
index 0000000..f3cf30d
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/trajectory/TrajectoryUtil.cpp
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/trajectory/TrajectoryUtil.h"
+
+#include <system_error>
+
+#include <wpi/SmallString.h>
+#include <wpi/json.h>
+#include <wpi/raw_istream.h>
+#include <wpi/raw_ostream.h>
+
+using namespace frc;
+
+void TrajectoryUtil::ToPathweaverJson(const Trajectory& trajectory,
+                                      const wpi::Twine& path) {
+  std::error_code error_code;
+
+  wpi::SmallString<128> buf;
+  wpi::raw_fd_ostream output{path.toStringRef(buf), error_code};
+  if (error_code) {
+    throw std::runtime_error(("Cannot open file: " + path).str());
+  }
+
+  wpi::json json = trajectory.States();
+  output << json;
+  output.flush();
+}
+
+Trajectory TrajectoryUtil::FromPathweaverJson(const wpi::Twine& path) {
+  std::error_code error_code;
+
+  wpi::SmallString<128> buf;
+  wpi::raw_fd_istream input{path.toStringRef(buf), error_code};
+  if (error_code) {
+    throw std::runtime_error(("Cannot open file: " + path).str());
+  }
+
+  wpi::json json;
+  input >> json;
+
+  return Trajectory{json.get<std::vector<Trajectory::State>>()};
+}
+
+std::string TrajectoryUtil::SerializeTrajectory(const Trajectory& trajectory) {
+  wpi::json json = trajectory.States();
+  return json.dump();
+}
+
+Trajectory TrajectoryUtil::DeserializeTrajectory(
+    const wpi::StringRef json_str) {
+  wpi::json json = wpi::json::parse(json_str);
+  return Trajectory{json.get<std::vector<Trajectory::State>>()};
+}
diff --git a/wpilibc/src/main/native/cpp/trajectory/constraint/CentripetalAccelerationConstraint.cpp b/wpilibc/src/main/native/cpp/trajectory/constraint/CentripetalAccelerationConstraint.cpp
new file mode 100644
index 0000000..bf45c34
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/trajectory/constraint/CentripetalAccelerationConstraint.cpp
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/trajectory/constraint/CentripetalAccelerationConstraint.h"
+
+using namespace frc;
+
+CentripetalAccelerationConstraint::CentripetalAccelerationConstraint(
+    units::meters_per_second_squared_t maxCentripetalAcceleration)
+    : m_maxCentripetalAcceleration(maxCentripetalAcceleration) {}
+
+units::meters_per_second_t CentripetalAccelerationConstraint::MaxVelocity(
+    const Pose2d& pose, curvature_t curvature,
+    units::meters_per_second_t velocity) {
+  // ac = v^2 / r
+  // k (curvature) = 1 / r
+
+  // therefore, ac = v^2 * k
+  // ac / k = v^2
+  // v = std::sqrt(ac / k)
+
+  // We have to multiply by 1_rad here to get the units to cancel out nicely.
+  // The units library defines a unit for radians although it is technically
+  // unitless.
+  return units::math::sqrt(m_maxCentripetalAcceleration /
+                           units::math::abs(curvature) * 1_rad);
+}
+
+TrajectoryConstraint::MinMax
+CentripetalAccelerationConstraint::MinMaxAcceleration(
+    const Pose2d& pose, curvature_t curvature,
+    units::meters_per_second_t speed) {
+  // The acceleration of the robot has no impact on the centripetal acceleration
+  // of the robot.
+  return {};
+}
diff --git a/wpilibc/src/main/native/cpp/trajectory/constraint/DifferentialDriveKinematicsConstraint.cpp b/wpilibc/src/main/native/cpp/trajectory/constraint/DifferentialDriveKinematicsConstraint.cpp
new file mode 100644
index 0000000..8b88bf4
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/trajectory/constraint/DifferentialDriveKinematicsConstraint.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h"
+
+using namespace frc;
+
+DifferentialDriveKinematicsConstraint::DifferentialDriveKinematicsConstraint(
+    DifferentialDriveKinematics kinematics, units::meters_per_second_t maxSpeed)
+    : m_kinematics(kinematics), m_maxSpeed(maxSpeed) {}
+
+units::meters_per_second_t DifferentialDriveKinematicsConstraint::MaxVelocity(
+    const Pose2d& pose, curvature_t curvature,
+    units::meters_per_second_t velocity) {
+  auto wheelSpeeds =
+      m_kinematics.ToWheelSpeeds({velocity, 0_mps, velocity * curvature});
+  wheelSpeeds.Normalize(m_maxSpeed);
+
+  return m_kinematics.ToChassisSpeeds(wheelSpeeds).vx;
+}
+
+TrajectoryConstraint::MinMax
+DifferentialDriveKinematicsConstraint::MinMaxAcceleration(
+    const Pose2d& pose, curvature_t curvature,
+    units::meters_per_second_t speed) {
+  return {};
+}
diff --git a/wpilibc/src/main/native/cpp/trajectory/constraint/DifferentialDriveVoltageConstraint.cpp b/wpilibc/src/main/native/cpp/trajectory/constraint/DifferentialDriveVoltageConstraint.cpp
new file mode 100644
index 0000000..3d6b61c
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/trajectory/constraint/DifferentialDriveVoltageConstraint.cpp
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/trajectory/constraint/DifferentialDriveVoltageConstraint.h"
+
+#include <algorithm>
+#include <limits>
+
+#include <wpi/MathExtras.h>
+
+using namespace frc;
+
+DifferentialDriveVoltageConstraint::DifferentialDriveVoltageConstraint(
+    SimpleMotorFeedforward<units::meter> feedforward,
+    DifferentialDriveKinematics kinematics, units::volt_t maxVoltage)
+    : m_feedforward(feedforward),
+      m_kinematics(kinematics),
+      m_maxVoltage(maxVoltage) {}
+
+units::meters_per_second_t DifferentialDriveVoltageConstraint::MaxVelocity(
+    const Pose2d& pose, curvature_t curvature,
+    units::meters_per_second_t velocity) {
+  return units::meters_per_second_t(std::numeric_limits<double>::max());
+}
+
+TrajectoryConstraint::MinMax
+DifferentialDriveVoltageConstraint::MinMaxAcceleration(
+    const Pose2d& pose, curvature_t curvature,
+    units::meters_per_second_t speed) {
+  auto wheelSpeeds =
+      m_kinematics.ToWheelSpeeds({speed, 0_mps, speed * curvature});
+
+  auto maxWheelSpeed = std::max(wheelSpeeds.left, wheelSpeeds.right);
+  auto minWheelSpeed = std::min(wheelSpeeds.left, wheelSpeeds.right);
+
+  // Calculate maximum/minimum possible accelerations from motor dynamics
+  // and max/min wheel speeds
+  auto maxWheelAcceleration =
+      m_feedforward.MaxAchievableAcceleration(m_maxVoltage, maxWheelSpeed);
+  auto minWheelAcceleration =
+      m_feedforward.MinAchievableAcceleration(m_maxVoltage, minWheelSpeed);
+
+  // Robot chassis turning on radius = 1/|curvature|.  Outer wheel has radius
+  // increased by half of the trackwidth T.  Inner wheel has radius decreased
+  // by half of the trackwidth.  Achassis / radius = Aouter / (radius + T/2), so
+  // Achassis = Aouter * radius / (radius + T/2) = Aouter / (1 + |curvature|T/2)
+  // Inner wheel is similar.
+
+  // sgn(speed) term added to correctly account for which wheel is on
+  // outside of turn:
+  // If moving forward, max acceleration constraint corresponds to wheel on
+  // outside of turn
+  // If moving backward, max acceleration constraint corresponds to wheel on
+  // inside of turn
+  auto maxChassisAcceleration =
+      maxWheelAcceleration /
+      (1 + m_kinematics.trackWidth * units::math::abs(curvature) *
+               wpi::sgn(speed) / (2_rad));
+  auto minChassisAcceleration =
+      minWheelAcceleration /
+      (1 - m_kinematics.trackWidth * units::math::abs(curvature) *
+               wpi::sgn(speed) / (2_rad));
+
+  // Negate acceleration corresponding to wheel on inside of turn
+  // if center of turn is inside of wheelbase
+  if ((m_kinematics.trackWidth / 2) > 1_rad / units::math::abs(curvature)) {
+    if (speed > 0_mps) {
+      minChassisAcceleration = -minChassisAcceleration;
+    } else {
+      maxChassisAcceleration = -maxChassisAcceleration;
+    }
+  }
+
+  return {minChassisAcceleration, maxChassisAcceleration};
+}
diff --git a/wpilibc/src/main/native/cpp/trajectory/constraint/MecanumDriveKinematicsConstraint.cpp b/wpilibc/src/main/native/cpp/trajectory/constraint/MecanumDriveKinematicsConstraint.cpp
new file mode 100644
index 0000000..2fd8151
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/trajectory/constraint/MecanumDriveKinematicsConstraint.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/trajectory/constraint/MecanumDriveKinematicsConstraint.h"
+
+using namespace frc;
+
+MecanumDriveKinematicsConstraint::MecanumDriveKinematicsConstraint(
+    MecanumDriveKinematics kinematics, units::meters_per_second_t maxSpeed)
+    : m_kinematics(kinematics), m_maxSpeed(maxSpeed) {}
+
+units::meters_per_second_t MecanumDriveKinematicsConstraint::MaxVelocity(
+    const Pose2d& pose, curvature_t curvature,
+    units::meters_per_second_t velocity) {
+  auto xVelocity = velocity * pose.Rotation().Cos();
+  auto yVelocity = velocity * pose.Rotation().Sin();
+  auto wheelSpeeds =
+      m_kinematics.ToWheelSpeeds({xVelocity, yVelocity, velocity * curvature});
+  wheelSpeeds.Normalize(m_maxSpeed);
+
+  auto normSpeeds = m_kinematics.ToChassisSpeeds(wheelSpeeds);
+
+  return units::math::hypot(normSpeeds.vx, normSpeeds.vy);
+}
+
+TrajectoryConstraint::MinMax
+MecanumDriveKinematicsConstraint::MinMaxAcceleration(
+    const Pose2d& pose, curvature_t curvature,
+    units::meters_per_second_t speed) {
+  return {};
+}
diff --git a/wpilibc/src/main/native/cppcs/RobotBase.cpp b/wpilibc/src/main/native/cppcs/RobotBase.cpp
new file mode 100644
index 0000000..eaf4ddc
--- /dev/null
+++ b/wpilibc/src/main/native/cppcs/RobotBase.cpp
@@ -0,0 +1,160 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/RobotBase.h"
+
+#ifdef __FRC_ROBORIO__
+#include <dlfcn.h>
+#endif
+
+#include <cstdio>
+
+#include <cameraserver/CameraServerShared.h>
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+#include <networktables/NetworkTableInstance.h>
+
+#include "WPILibVersion.h"
+#include "frc/DriverStation.h"
+#include "frc/RobotState.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+#include "frc/livewindow/LiveWindow.h"
+#include "frc/smartdashboard/SmartDashboard.h"
+
+typedef void (*SetCameraServerSharedFP)(frc::CameraServerShared* shared);
+
+using namespace frc;
+
+int frc::RunHALInitialization() {
+  if (!HAL_Initialize(500, 0)) {
+    wpi::errs() << "FATAL ERROR: HAL could not be initialized\n";
+    return -1;
+  }
+  HAL_Report(HALUsageReporting::kResourceType_Language,
+             HALUsageReporting::kLanguage_CPlusPlus, 0, GetWPILibVersion());
+  wpi::outs() << "\n********** Robot program starting **********\n";
+  return 0;
+}
+
+std::thread::id RobotBase::m_threadId;
+
+namespace {
+class WPILibCameraServerShared : public frc::CameraServerShared {
+ public:
+  void ReportUsbCamera(int id) override {
+    HAL_Report(HALUsageReporting::kResourceType_UsbCamera, id);
+  }
+  void ReportAxisCamera(int id) override {
+    HAL_Report(HALUsageReporting::kResourceType_AxisCamera, id);
+  }
+  void ReportVideoServer(int id) override {
+    HAL_Report(HALUsageReporting::kResourceType_PCVideoServer, id);
+  }
+  void SetCameraServerError(const wpi::Twine& error) override {
+    wpi_setGlobalWPIErrorWithContext(CameraServerError, error);
+  }
+  void SetVisionRunnerError(const wpi::Twine& error) override {
+    wpi_setGlobalErrorWithContext(-1, error);
+  }
+  void ReportDriverStationError(const wpi::Twine& error) override {
+    DriverStation::ReportError(error);
+  }
+  std::pair<std::thread::id, bool> GetRobotMainThreadId() const override {
+    return std::make_pair(RobotBase::GetThreadId(), true);
+  }
+};
+}  // namespace
+
+static void SetupCameraServerShared() {
+#ifdef __FRC_ROBORIO__
+#ifdef DYNAMIC_CAMERA_SERVER
+#ifdef DYNAMIC_CAMERA_SERVER_DEBUG
+  auto cameraServerLib = dlopen("libcameraserverd.so", RTLD_NOW);
+#else
+  auto cameraServerLib = dlopen("libcameraserver.so", RTLD_NOW);
+#endif
+
+  if (!cameraServerLib) {
+    wpi::outs() << "Camera Server Library Not Found\n";
+    wpi::outs().flush();
+    return;
+  }
+  auto symbol = dlsym(cameraServerLib, "CameraServer_SetCameraServerShared");
+  if (symbol) {
+    auto setCameraServerShared = (SetCameraServerSharedFP)symbol;
+    setCameraServerShared(new WPILibCameraServerShared{});
+    wpi::outs() << "Set Camera Server Shared\n";
+    wpi::outs().flush();
+  } else {
+    wpi::outs() << "Camera Server Shared Symbol Missing\n";
+    wpi::outs().flush();
+  }
+#else
+  CameraServer_SetCameraServerShared(new WPILibCameraServerShared{});
+#endif
+#else
+  wpi::outs() << "Not loading CameraServerShared\n";
+  wpi::outs().flush();
+#endif
+}
+
+bool RobotBase::IsEnabled() const { return m_ds.IsEnabled(); }
+
+bool RobotBase::IsDisabled() const { return m_ds.IsDisabled(); }
+
+bool RobotBase::IsAutonomous() const { return m_ds.IsAutonomous(); }
+
+bool RobotBase::IsOperatorControl() const { return m_ds.IsOperatorControl(); }
+
+bool RobotBase::IsTest() const { return m_ds.IsTest(); }
+
+bool RobotBase::IsNewDataAvailable() const { return m_ds.IsNewControlData(); }
+
+std::thread::id RobotBase::GetThreadId() { return m_threadId; }
+
+RobotBase::RobotBase() : m_ds(DriverStation::GetInstance()) {
+  m_threadId = std::this_thread::get_id();
+
+  SetupCameraServerShared();
+
+  auto inst = nt::NetworkTableInstance::GetDefault();
+  inst.SetNetworkIdentity("Robot");
+#ifdef __FRC_ROBORIO__
+  inst.StartServer("/home/lvuser/networktables.ini");
+#else
+  inst.StartServer();
+#endif
+
+  SmartDashboard::init();
+
+  if (IsReal()) {
+    std::FILE* file = nullptr;
+    file = std::fopen("/tmp/frc_versions/FRC_Lib_Version.ini", "w");
+
+    if (file != nullptr) {
+      std::fputs("C++ ", file);
+      std::fputs(GetWPILibVersion(), file);
+      std::fclose(file);
+    }
+  }
+
+  // First and one-time initialization
+  inst.GetTable("LiveWindow")
+      ->GetSubTable(".status")
+      ->GetEntry("LW Enabled")
+      .SetBoolean(false);
+
+  LiveWindow::GetInstance()->SetEnabled(false);
+}
+
+RobotBase::RobotBase(RobotBase&&) noexcept
+    : m_ds(DriverStation::GetInstance()) {}
+
+RobotBase::~RobotBase() {}
+
+RobotBase& RobotBase::operator=(RobotBase&&) noexcept { return *this; }
diff --git a/wpilibc/src/main/native/include/WPILibVersion.h b/wpilibc/src/main/native/include/WPILibVersion.h
new file mode 100644
index 0000000..8aab880
--- /dev/null
+++ b/wpilibc/src/main/native/include/WPILibVersion.h
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/*
+ * The corresponding WPILibVersion.cpp file is autogenerated by the build
+ * system. If it does not exist, make sure that you run a build.
+ */
+extern const char* GetWPILibVersion();
diff --git a/wpilibc/src/main/native/include/frc/ADXL345_I2C.h b/wpilibc/src/main/native/include/frc/ADXL345_I2C.h
new file mode 100644
index 0000000..202acbb
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/ADXL345_I2C.h
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared 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/SimDevice.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/I2C.h"
+#include "frc/interfaces/Accelerometer.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+
+/**
+ * ADXL345 Accelerometer on I2C.
+ *
+ * This class allows access to a Analog Devices ADXL345 3-axis accelerometer on
+ * an I2C bus. This class assumes the default (not alternate) sensor address of
+ * 0x1D (7-bit address).
+ */
+class ADXL345_I2C : public ErrorBase,
+                    public Accelerometer,
+                    public Sendable,
+                    public SendableHelper<ADXL345_I2C> {
+ public:
+  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
+
+  struct AllAxes {
+    double XAxis;
+    double YAxis;
+    double ZAxis;
+  };
+
+  /**
+   * Constructs the ADXL345 Accelerometer over I2C.
+   *
+   * @param port          The I2C port the accelerometer is attached to
+   * @param range         The range (+ or -) that the accelerometer will measure
+   * @param deviceAddress The I2C address of the accelerometer (0x1D or 0x53)
+   */
+  explicit ADXL345_I2C(I2C::Port port, Range range = kRange_2G,
+                       int deviceAddress = kAddress);
+  ~ADXL345_I2C() override = default;
+
+  ADXL345_I2C(ADXL345_I2C&&) = default;
+  ADXL345_I2C& operator=(ADXL345_I2C&&) = default;
+
+  // Accelerometer interface
+  void SetRange(Range range) override;
+  double GetX() override;
+  double GetY() override;
+  double GetZ() override;
+
+  /**
+   * Get the acceleration of one axis in Gs.
+   *
+   * @param axis The axis to read from.
+   * @return Acceleration of the ADXL345 in Gs.
+   */
+  virtual double GetAcceleration(Axes axis);
+
+  /**
+   * Get the acceleration of all axes in Gs.
+   *
+   * @return An object containing the acceleration measured on each axis of the
+   *         ADXL345 in Gs.
+   */
+  virtual AllAxes GetAccelerations();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ protected:
+  I2C m_i2c;
+
+  hal::SimDevice m_simDevice;
+  hal::SimEnum m_simRange;
+  hal::SimDouble m_simX;
+  hal::SimDouble m_simY;
+  hal::SimDouble m_simZ;
+
+  static constexpr int kAddress = 0x1D;
+  static constexpr int kPowerCtlRegister = 0x2D;
+  static constexpr int kDataFormatRegister = 0x31;
+  static constexpr int kDataRegister = 0x32;
+  static constexpr double kGsPerLSB = 0.00390625;
+
+  enum PowerCtlFields {
+    kPowerCtl_Link = 0x20,
+    kPowerCtl_AutoSleep = 0x10,
+    kPowerCtl_Measure = 0x08,
+    kPowerCtl_Sleep = 0x04
+  };
+
+  enum DataFormatFields {
+    kDataFormat_SelfTest = 0x80,
+    kDataFormat_SPI = 0x40,
+    kDataFormat_IntInvert = 0x20,
+    kDataFormat_FullRes = 0x08,
+    kDataFormat_Justify = 0x04
+  };
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/ADXL345_SPI.h b/wpilibc/src/main/native/include/frc/ADXL345_SPI.h
new file mode 100644
index 0000000..90454c0
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/ADXL345_SPI.h
@@ -0,0 +1,108 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared 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/SimDevice.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/SPI.h"
+#include "frc/interfaces/Accelerometer.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+/**
+ * ADXL345 Accelerometer on SPI.
+ *
+ * This class allows access to an Analog Devices ADXL345 3-axis accelerometer
+ * via SPI. This class assumes the sensor is wired in 4-wire SPI mode.
+ */
+class ADXL345_SPI : public ErrorBase,
+                    public Accelerometer,
+                    public Sendable,
+                    public SendableHelper<ADXL345_SPI> {
+ public:
+  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
+
+  struct AllAxes {
+    double XAxis;
+    double YAxis;
+    double ZAxis;
+  };
+
+  /**
+   * Constructor.
+   *
+   * @param port  The SPI port the accelerometer is attached to
+   * @param range The range (+ or -) that the accelerometer will measure
+   */
+  explicit ADXL345_SPI(SPI::Port port, Range range = kRange_2G);
+
+  ~ADXL345_SPI() override = default;
+
+  ADXL345_SPI(ADXL345_SPI&&) = default;
+  ADXL345_SPI& operator=(ADXL345_SPI&&) = default;
+
+  // Accelerometer interface
+  void SetRange(Range range) override;
+  double GetX() override;
+  double GetY() override;
+  double GetZ() override;
+
+  /**
+   * Get the acceleration of one axis in Gs.
+   *
+   * @param axis The axis to read from.
+   * @return Acceleration of the ADXL345 in Gs.
+   */
+  virtual double GetAcceleration(Axes axis);
+
+  /**
+   * Get the acceleration of all axes in Gs.
+   *
+   * @return An object containing the acceleration measured on each axis of the
+   *         ADXL345 in Gs.
+   */
+  virtual AllAxes GetAccelerations();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ protected:
+  SPI m_spi;
+
+  hal::SimDevice m_simDevice;
+  hal::SimEnum m_simRange;
+  hal::SimDouble m_simX;
+  hal::SimDouble m_simY;
+  hal::SimDouble m_simZ;
+
+  static constexpr int kPowerCtlRegister = 0x2D;
+  static constexpr int kDataFormatRegister = 0x31;
+  static constexpr int kDataRegister = 0x32;
+  static constexpr double kGsPerLSB = 0.00390625;
+
+  enum SPIAddressFields { kAddress_Read = 0x80, kAddress_MultiByte = 0x40 };
+
+  enum PowerCtlFields {
+    kPowerCtl_Link = 0x20,
+    kPowerCtl_AutoSleep = 0x10,
+    kPowerCtl_Measure = 0x08,
+    kPowerCtl_Sleep = 0x04
+  };
+
+  enum DataFormatFields {
+    kDataFormat_SelfTest = 0x80,
+    kDataFormat_SPI = 0x40,
+    kDataFormat_IntInvert = 0x20,
+    kDataFormat_FullRes = 0x08,
+    kDataFormat_Justify = 0x04
+  };
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/ADXL362.h b/wpilibc/src/main/native/include/frc/ADXL362.h
new file mode 100644
index 0000000..e1d659b
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/ADXL362.h
@@ -0,0 +1,94 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared 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/SimDevice.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/SPI.h"
+#include "frc/interfaces/Accelerometer.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+
+/**
+ * ADXL362 SPI Accelerometer.
+ *
+ * This class allows access to an Analog Devices ADXL362 3-axis accelerometer.
+ */
+class ADXL362 : public ErrorBase,
+                public Accelerometer,
+                public Sendable,
+                public SendableHelper<ADXL362> {
+ public:
+  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
+  struct AllAxes {
+    double XAxis;
+    double YAxis;
+    double ZAxis;
+  };
+
+ public:
+  /**
+   * Constructor.  Uses the onboard CS1.
+   *
+   * @param range The range (+ or -) that the accelerometer will measure.
+   */
+  explicit ADXL362(Range range = kRange_2G);
+
+  /**
+   * Constructor.
+   *
+   * @param port  The SPI port the accelerometer is attached to
+   * @param range The range (+ or -) that the accelerometer will measure.
+   */
+  explicit ADXL362(SPI::Port port, Range range = kRange_2G);
+
+  ~ADXL362() override = default;
+
+  ADXL362(ADXL362&&) = default;
+  ADXL362& operator=(ADXL362&&) = default;
+
+  // Accelerometer interface
+  void SetRange(Range range) override;
+  double GetX() override;
+  double GetY() override;
+  double GetZ() override;
+
+  /**
+   * Get the acceleration of one axis in Gs.
+   *
+   * @param axis The axis to read from.
+   * @return Acceleration of the ADXL362 in Gs.
+   */
+  virtual double GetAcceleration(Axes axis);
+
+  /**
+   * Get the acceleration of all axes in Gs.
+   *
+   * @return An object containing the acceleration measured on each axis of the
+   *         ADXL362 in Gs.
+   */
+  virtual AllAxes GetAccelerations();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  SPI m_spi;
+  hal::SimDevice m_simDevice;
+  hal::SimEnum m_simRange;
+  hal::SimDouble m_simX;
+  hal::SimDouble m_simY;
+  hal::SimDouble m_simZ;
+  double m_gsPerLSB = 0.001;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h b/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h
new file mode 100644
index 0000000..ccdb75c
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h
@@ -0,0 +1,106 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <hal/SimDevice.h>
+
+#include "frc/GyroBase.h"
+#include "frc/SPI.h"
+
+namespace frc {
+
+/**
+ * Use a rate gyro to return the robots heading relative to a starting position.
+ *
+ * The Gyro class tracks the robots heading based on the starting position. As
+ * the robot rotates the new heading is computed by integrating the rate of
+ * rotation returned by the sensor. When the class is instantiated, it does a
+ * short calibration routine where it samples the gyro while at rest to
+ * determine the default offset. This is subtracted from each sample to
+ * determine the heading.
+ *
+ * This class is for the digital ADXRS450 gyro sensor that connects via SPI.
+ */
+class ADXRS450_Gyro : public GyroBase {
+ public:
+  /**
+   * Gyro constructor on onboard CS0.
+   */
+  ADXRS450_Gyro();
+
+  /**
+   * Gyro constructor on the specified SPI port.
+   *
+   * @param port The SPI port the gyro is attached to.
+   */
+  explicit ADXRS450_Gyro(SPI::Port port);
+
+  ~ADXRS450_Gyro() override = default;
+
+  ADXRS450_Gyro(ADXRS450_Gyro&&) = default;
+  ADXRS450_Gyro& operator=(ADXRS450_Gyro&&) = default;
+
+  /**
+   * Return the actual angle in degrees that the robot is currently facing.
+   *
+   * The angle is based on the current accumulator value corrected by the
+   * oversampling rate, the gyro type and the A/D calibration values.
+   * The angle is continuous, that is it will continue from 360->361 degrees.
+   * This allows algorithms that wouldn't want to see a discontinuity in the
+   * gyro output as it sweeps from 360 to 0 on the second time around.
+   *
+   * @return the current heading of the robot in degrees. This heading is based
+   *         on integration of the returned rate from the gyro.
+   */
+  double GetAngle() const override;
+
+  /**
+   * Return the rate of rotation of the gyro
+   *
+   * The rate is based on the most recent reading of the gyro analog value
+   *
+   * @return the current rate in degrees per second
+   */
+  double GetRate() const override;
+
+  /**
+   * Reset the gyro.
+   *
+   * Resets the gyro to a heading of zero. This can be used if there is
+   * significant drift in the gyro and it needs to be recalibrated after it has
+   * been running.
+   */
+  void Reset() override;
+
+  /**
+   * Initialize the gyro.
+   *
+   * Calibrate the gyro by running for a number of samples and computing the
+   * center value. Then use the center value as the Accumulator center value for
+   * subsequent measurements.
+   *
+   * It's important to make sure that the robot is not moving while the
+   * centering calculations are in progress, this is typically done when the
+   * robot is first turned on while it's sitting at rest before the competition
+   * starts.
+   */
+  void Calibrate() override;
+
+ private:
+  SPI m_spi;
+
+  hal::SimDevice m_simDevice;
+  hal::SimDouble m_simAngle;
+  hal::SimDouble m_simRate;
+
+  uint16_t ReadRegister(int reg);
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/AddressableLED.h b/wpilibc/src/main/native/include/frc/AddressableLED.h
new file mode 100644
index 0000000..5534ae4
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/AddressableLED.h
@@ -0,0 +1,163 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <hal/AddressableLEDTypes.h>
+#include <hal/Types.h>
+#include <units/units.h>
+#include <wpi/ArrayRef.h>
+
+#include "frc/ErrorBase.h"
+#include "util/Color.h"
+#include "util/Color8Bit.h"
+
+namespace frc {
+
+/**
+ * A class for driving addressable LEDs, such as WS2812s and NeoPixels.
+ */
+class AddressableLED : public ErrorBase {
+ public:
+  class LEDData : public HAL_AddressableLEDData {
+   public:
+    LEDData() : LEDData(0, 0, 0) {}
+    LEDData(int _r, int _g, int _b) {
+      r = _r;
+      g = _g;
+      b = _b;
+      padding = 0;
+    }
+
+    /**
+     * A helper method to set all values of the LED.
+     *
+     * @param r the r value [0-255]
+     * @param g the g value [0-255]
+     * @param b the b value [0-255]
+     */
+    void SetRGB(int r, int g, int b) {
+      this->r = r;
+      this->g = g;
+      this->b = b;
+    }
+
+    /**
+     * A helper method to set all values of the LED.
+     *
+     * @param h the h value [0-180]
+     * @param s the s value [0-255]
+     * @param v the v value [0-255]
+     */
+    void SetHSV(int h, int s, int v);
+
+    /*
+     * Sets a specific LED in the buffer.
+     *
+     * @param color The color of the LED
+     */
+    void SetLED(const Color& color) {
+      this->r = color.red * 255;
+      this->g = color.green * 255;
+      this->b = color.blue * 255;
+    }
+
+    /*
+     * Sets a specific LED in the buffer.
+     *
+     * @param color The color of the LED
+     */
+    void SetLED(const Color8Bit& color) {
+      this->r = color.red;
+      this->g = color.green;
+      this->b = color.blue;
+    }
+  };
+
+  /**
+   * Constructs a new driver for a specific port.
+   *
+   * @param port the output port to use (Must be a PWM port)
+   */
+  explicit AddressableLED(int port);
+
+  ~AddressableLED() override;
+
+  /**
+   * Sets the length of the LED strip.
+   *
+   * <p>Calling this is an expensive call, so its best to call it once, then
+   * just update data.
+   *
+   * @param length the strip length
+   */
+  void SetLength(int length);
+
+  /**
+   * Sets the led output data.
+   *
+   * <p>If the output is enabled, this will start writing the next data cycle.
+   * It is safe to call, even while output is enabled.
+   *
+   * @param ledData the buffer to write
+   */
+  void SetData(wpi::ArrayRef<LEDData> ledData);
+
+  /**
+   * Sets the led output data.
+   *
+   * <p>If the output is enabled, this will start writing the next data cycle.
+   * It is safe to call, even while output is enabled.
+   *
+   * @param ledData the buffer to write
+   */
+  void SetData(std::initializer_list<LEDData> ledData);
+
+  /**
+   * Sets the bit timing.
+   *
+   * <p>By default, the driver is set up to drive WS2812s, so nothing needs to
+   * be set for those.
+   *
+   * @param lowTime0 low time for 0 bit
+   * @param highTime0 high time for 0 bit
+   * @param lowTime1 low time for 1 bit
+   * @param highTime1 high time for 1 bit
+   */
+  void SetBitTiming(units::nanosecond_t lowTime0, units::nanosecond_t highTime0,
+                    units::nanosecond_t lowTime1,
+                    units::nanosecond_t highTime1);
+
+  /**
+   * Sets the sync time.
+   *
+   * <p>The sync time is the time to hold output so LEDs enable. Default set for
+   * WS2812.
+   *
+   * @param syncTimeMicroSeconds the sync time
+   */
+  void SetSyncTime(units::microsecond_t syncTime);
+
+  /**
+   * Starts the output.
+   *
+   * <p>The output writes continously.
+   */
+  void Start();
+
+  /**
+   * Stops the output.
+   */
+  void Stop();
+
+ private:
+  hal::Handle<HAL_DigitalHandle> m_pwmHandle;
+  hal::Handle<HAL_AddressableLEDHandle> m_handle;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/AnalogAccelerometer.h b/wpilibc/src/main/native/include/frc/AnalogAccelerometer.h
new file mode 100644
index 0000000..27015e4
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/AnalogAccelerometer.h
@@ -0,0 +1,123 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include "frc/AnalogInput.h"
+#include "frc/ErrorBase.h"
+#include "frc/PIDSource.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+
+/**
+ * Handle operation of an analog accelerometer.
+ *
+ * The accelerometer reads acceleration directly through the sensor. Many
+ * sensors have multiple axis and can be treated as multiple devices. Each is
+ * calibrated by finding the center value over a period of time.
+ */
+class AnalogAccelerometer : public ErrorBase,
+                            public PIDSource,
+                            public Sendable,
+                            public SendableHelper<AnalogAccelerometer> {
+ public:
+  /**
+   * Create a new instance of an accelerometer.
+   *
+   * The constructor allocates desired analog input.
+   *
+   * @param channel The channel number for the analog input the accelerometer is
+   *                connected to
+   */
+  explicit AnalogAccelerometer(int channel);
+
+  /**
+   * Create a new instance of Accelerometer from an existing AnalogInput.
+   *
+   * Make a new instance of accelerometer given an AnalogInput. This is
+   * particularly useful if the port is going to be read as an analog channel as
+   * well as through the Accelerometer class.
+   *
+   * @param channel The existing AnalogInput object for the analog input the
+   *                accelerometer is connected to
+   */
+  explicit AnalogAccelerometer(AnalogInput* channel);
+
+  /**
+   * Create a new instance of Accelerometer from an existing AnalogInput.
+   *
+   * Make a new instance of accelerometer given an AnalogInput. This is
+   * particularly useful if the port is going to be read as an analog channel as
+   * well as through the Accelerometer class.
+   *
+   * @param channel The existing AnalogInput object for the analog input the
+   *                accelerometer is connected to
+   */
+  explicit AnalogAccelerometer(std::shared_ptr<AnalogInput> channel);
+
+  ~AnalogAccelerometer() override = default;
+
+  AnalogAccelerometer(AnalogAccelerometer&&) = default;
+  AnalogAccelerometer& operator=(AnalogAccelerometer&&) = default;
+
+  /**
+   * Return the acceleration in Gs.
+   *
+   * The acceleration is returned units of Gs.
+   *
+   * @return The current acceleration of the sensor in Gs.
+   */
+  double GetAcceleration() const;
+
+  /**
+   * Set the accelerometer sensitivity.
+   *
+   * This sets the sensitivity of the accelerometer used for calculating the
+   * acceleration. The sensitivity varies by accelerometer model. There are
+   * constants defined for various models.
+   *
+   * @param sensitivity The sensitivity of accelerometer in Volts per G.
+   */
+  void SetSensitivity(double sensitivity);
+
+  /**
+   * Set the voltage that corresponds to 0 G.
+   *
+   * The zero G voltage varies by accelerometer model. There are constants
+   * defined for various models.
+   *
+   * @param zero The zero G voltage.
+   */
+  void SetZero(double zero);
+
+  /**
+   * Get the Acceleration for the PID Source parent.
+   *
+   * @return The current acceleration in Gs.
+   */
+  double PIDGet() override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  /**
+   * Common function for initializing the accelerometer.
+   */
+  void InitAccelerometer();
+
+  std::shared_ptr<AnalogInput> m_analogInput;
+  double m_voltsPerG = 1.0;
+  double m_zeroGVoltage = 2.5;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/AnalogEncoder.h b/wpilibc/src/main/native/include/frc/AnalogEncoder.h
new file mode 100644
index 0000000..872db87
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/AnalogEncoder.h
@@ -0,0 +1,126 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <hal/SimDevice.h>
+#include <hal/Types.h>
+#include <units/units.h>
+
+#include "frc/AnalogTrigger.h"
+#include "frc/Counter.h"
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+class AnalogInput;
+
+/**
+ * Class for supporting continuous analog encoders, such as the US Digital MA3.
+ */
+class AnalogEncoder : public ErrorBase,
+                      public Sendable,
+                      public SendableHelper<AnalogEncoder> {
+ public:
+  /**
+   * Construct a new AnalogEncoder attached to a specific AnalogInput.
+   *
+   * @param analogInput the analog input to attach to
+   */
+  explicit AnalogEncoder(AnalogInput& analogInput);
+
+  /**
+   * Construct a new AnalogEncoder attached to a specific AnalogInput.
+   *
+   * @param analogInput the analog input to attach to
+   */
+  explicit AnalogEncoder(AnalogInput* analogInput);
+
+  /**
+   * Construct a new AnalogEncoder attached to a specific AnalogInput.
+   *
+   * @param analogInput the analog input to attach to
+   */
+  explicit AnalogEncoder(std::shared_ptr<AnalogInput> analogInput);
+
+  ~AnalogEncoder() override = default;
+
+  AnalogEncoder(AnalogEncoder&&) = default;
+  AnalogEncoder& operator=(AnalogEncoder&&) = default;
+
+  /**
+   * Reset the Encoder distance to zero.
+   */
+  void Reset();
+
+  /**
+   * Get the encoder value since the last reset.
+   *
+   * This is reported in rotations since the last reset.
+   *
+   * @return the encoder value in rotations
+   */
+  units::turn_t Get() const;
+
+  /**
+   * Get the offset of position relative to the last reset.
+   *
+   * GetPositionInRotation() - GetPositionOffset() will give an encoder absolute
+   * position relative to the last reset. This could potentially be negative,
+   * which needs to be accounted for.
+   *
+   * @return the position offset
+   */
+  double GetPositionOffset() const;
+
+  /**
+   * Set the distance per rotation of the encoder. This sets the multiplier used
+   * to determine the distance driven based on the rotation value from the
+   * encoder. Set this value based on the how far the mechanism travels in 1
+   * rotation of the encoder, and factor in gearing reductions following the
+   * encoder shaft. This distance can be in any units you like, linear or
+   * angular.
+   *
+   * @param distancePerRotation the distance per rotation of the encoder
+   */
+  void SetDistancePerRotation(double distancePerRotation);
+
+  /**
+   * Get the distance per rotation for this encoder.
+   *
+   * @return The scale factor that will be used to convert rotation to useful
+   * units.
+   */
+  double GetDistancePerRotation() const;
+
+  /**
+   * Get the distance the sensor has driven since the last reset as scaled by
+   * the value from SetDistancePerRotation.
+   *
+   * @return The distance driven since the last reset
+   */
+  double GetDistance() const;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  void Init();
+
+  std::shared_ptr<AnalogInput> m_analogInput;
+  AnalogTrigger m_analogTrigger;
+  Counter m_counter;
+  double m_positionOffset = 0;
+  double m_distancePerRotation = 1.0;
+  mutable units::turn_t m_lastPosition{0.0};
+
+  hal::SimDevice m_simDevice;
+  hal::SimDouble m_simPosition;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/AnalogGyro.h b/wpilibc/src/main/native/include/frc/AnalogGyro.h
new file mode 100644
index 0000000..bcc67c9
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/AnalogGyro.h
@@ -0,0 +1,196 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <hal/Types.h>
+
+#include "frc/GyroBase.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class AnalogInput;
+
+/**
+ * Use a rate gyro to return the robots heading relative to a starting position.
+ * The Gyro class tracks the robots heading based on the starting position. As
+ * the robot rotates the new heading is computed by integrating the rate of
+ * rotation returned by the sensor. When the class is instantiated, it does a
+ * short calibration routine where it samples the gyro while at rest to
+ * determine the default offset. This is subtracted from each sample to
+ * determine the heading. This gyro class must be used with a channel that is
+ * assigned one of the Analog accumulators from the FPGA. See AnalogInput for
+ * the current accumulator assignments.
+ *
+ * This class is for gyro sensors that connect to an analog input.
+ */
+class AnalogGyro : public GyroBase {
+ public:
+  static constexpr int kOversampleBits = 10;
+  static constexpr int kAverageBits = 0;
+  static constexpr double kSamplesPerSecond = 50.0;
+  static constexpr double kCalibrationSampleTime = 5.0;
+  static constexpr double kDefaultVoltsPerDegreePerSecond = 0.007;
+
+  /**
+   * Gyro constructor using the Analog Input channel number.
+   *
+   * @param channel The analog channel the gyro is connected to. Gyros can only
+   *                be used on on-board Analog Inputs 0-1.
+   */
+  explicit AnalogGyro(int channel);
+
+  /**
+   * Gyro constructor with a precreated AnalogInput object.
+   *
+   * Use this constructor when the analog channel needs to be shared.
+   * This object will not clean up the AnalogInput object when using this
+   * constructor.
+   *
+   * Gyros can only be used on on-board channels 0-1.
+   *
+   * @param channel A pointer to the AnalogInput object that the gyro is
+   *                connected to.
+   */
+  explicit AnalogGyro(AnalogInput* channel);
+
+  /**
+   * Gyro constructor with a precreated AnalogInput object.
+   *
+   * Use this constructor when the analog channel needs to be shared.
+   * This object will not clean up the AnalogInput object when using this
+   * constructor.
+   *
+   * @param channel A pointer to the AnalogInput object that the gyro is
+   *                connected to.
+   */
+  explicit AnalogGyro(std::shared_ptr<AnalogInput> channel);
+
+  /**
+   * Gyro constructor using the Analog Input channel number with parameters for
+   * presetting the center and offset values. Bypasses calibration.
+   *
+   * @param channel The analog channel the gyro is connected to. Gyros can only
+   *                be used on on-board Analog Inputs 0-1.
+   * @param center  Preset uncalibrated value to use as the accumulator center
+   *                value.
+   * @param offset  Preset uncalibrated value to use as the gyro offset.
+   */
+  AnalogGyro(int channel, int center, double offset);
+
+  /**
+   * Gyro constructor with a precreated AnalogInput object and calibrated
+   * parameters.
+   *
+   * Use this constructor when the analog channel needs to be shared.
+   * This object will not clean up the AnalogInput object when using this
+   * constructor.
+   *
+   * @param channel A pointer to the AnalogInput object that the gyro is
+   *                connected to.
+   * @param center  Preset uncalibrated value to use as the accumulator center
+   *                value.
+   * @param offset  Preset uncalibrated value to use as the gyro offset.
+   */
+  AnalogGyro(std::shared_ptr<AnalogInput> channel, int center, double offset);
+
+  ~AnalogGyro() override;
+
+  AnalogGyro(AnalogGyro&& rhs);
+  AnalogGyro& operator=(AnalogGyro&& rhs);
+
+  /**
+   * Return the actual angle in degrees that the robot is currently facing.
+   *
+   * The angle is based on the current accumulator value corrected by the
+   * oversampling rate, the gyro type and the A/D calibration values. The angle
+   * is continuous, that is it will continue from 360->361 degrees. This allows
+   * algorithms that wouldn't want to see a discontinuity in the gyro output as
+   * it sweeps from 360 to 0 on the second time around.
+   *
+   * @return The current heading of the robot in degrees. This heading is based
+   *         on integration of the returned rate from the gyro.
+   */
+  double GetAngle() const override;
+
+  /**
+   * Return the rate of rotation of the gyro
+   *
+   * The rate is based on the most recent reading of the gyro analog value
+   *
+   * @return the current rate in degrees per second
+   */
+  double GetRate() const override;
+
+  /**
+   * Return the gyro center value. If run after calibration,
+   * the center value can be used as a preset later.
+   *
+   * @return the current center value
+   */
+  virtual int GetCenter() const;
+
+  /**
+   * Return the gyro offset value. If run after calibration,
+   * the offset value can be used as a preset later.
+   *
+   * @return the current offset value
+   */
+  virtual double GetOffset() const;
+
+  /**
+   * Set the gyro sensitivity.
+   *
+   * This takes the number of volts/degree/second sensitivity of the gyro and
+   * uses it in subsequent calculations to allow the code to work with multiple
+   * gyros. This value is typically found in the gyro datasheet.
+   *
+   * @param voltsPerDegreePerSecond The sensitivity in Volts/degree/second
+   */
+  void SetSensitivity(double voltsPerDegreePerSecond);
+
+  /**
+   * Set the size of the neutral zone.
+   *
+   * Any voltage from the gyro less than this amount from the center is
+   * considered stationary.  Setting a deadband will decrease the amount of
+   * drift when the gyro isn't rotating, but will make it less accurate.
+   *
+   * @param volts The size of the deadband in volts
+   */
+  void SetDeadband(double volts);
+
+  /**
+   * Reset the gyro.
+   *
+   * Resets the gyro to a heading of zero. This can be used if there is
+   * significant drift in the gyro and it needs to be recalibrated after it has
+   * been running.
+   */
+  void Reset() override;
+
+  /**
+   * Initialize the gyro.
+   *
+   * Calibration is handled by Calibrate().
+   */
+  virtual void InitGyro();
+
+  void Calibrate() override;
+
+ protected:
+  std::shared_ptr<AnalogInput> m_analog;
+
+ private:
+  hal::Handle<HAL_GyroHandle> m_gyroHandle;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/AnalogInput.h b/wpilibc/src/main/native/include/frc/AnalogInput.h
new file mode 100644
index 0000000..3d14c4c
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/AnalogInput.h
@@ -0,0 +1,308 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <hal/Types.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/PIDSource.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+class DMA;
+class DMASample;
+
+/**
+ * Analog input class.
+ *
+ * Connected to each analog channel is an averaging and oversampling engine.
+ * This engine accumulates the specified ( by SetAverageBits() and
+ * SetOversampleBits() ) number of samples before returning a new value. This is
+ * not a sliding window average. The only difference between the oversampled
+ * samples and the averaged samples is that the oversampled samples are simply
+ * accumulated effectively increasing the resolution, while the averaged samples
+ * are divided by the number of samples to retain the resolution, but get more
+ * stable values.
+ */
+class AnalogInput : public ErrorBase,
+                    public PIDSource,
+                    public Sendable,
+                    public SendableHelper<AnalogInput> {
+  friend class AnalogTrigger;
+  friend class AnalogGyro;
+  friend class DMA;
+  friend class DMASample;
+
+ public:
+  static constexpr int kAccumulatorModuleNumber = 1;
+  static constexpr int kAccumulatorNumChannels = 2;
+  static constexpr int kAccumulatorChannels[kAccumulatorNumChannels] = {0, 1};
+
+  /**
+   * Construct an analog input.
+   *
+   * @param channel The channel number on the roboRIO to represent. 0-3 are
+   *                on-board 4-7 are on the MXP port.
+   */
+  explicit AnalogInput(int channel);
+
+  ~AnalogInput() override;
+
+  AnalogInput(AnalogInput&&) = default;
+  AnalogInput& operator=(AnalogInput&&) = default;
+
+  /**
+   * Get a sample straight from this channel.
+   *
+   * The sample is a 12-bit value representing the 0V to 5V range of the A/D
+   * converter in the module.  The units are in A/D converter codes.  Use
+   * GetVoltage() to get the analog value in calibrated units.
+   *
+   * @return A sample straight from this channel.
+   */
+  int GetValue() const;
+
+  /**
+   * Get a sample from the output of the oversample and average engine for this
+   * channel.
+   *
+   * The sample is 12-bit + the bits configured in SetOversampleBits().
+   * The value configured in SetAverageBits() will cause this value to be
+   * averaged 2**bits number of samples.
+   *
+   * This is not a sliding window. The sample will not change until
+   * 2**(OversampleBits + AverageBits) samples have been acquired from the
+   * module on this channel.
+   *
+   * Use GetAverageVoltage() to get the analog value in calibrated units.
+   *
+   * @return A sample from the oversample and average engine for this channel.
+   */
+  int GetAverageValue() const;
+
+  /**
+   * Get a scaled sample straight from this channel.
+   *
+   * The value is scaled to units of Volts using the calibrated scaling data
+   * from GetLSBWeight() and GetOffset().
+   *
+   * @return A scaled sample straight from this channel.
+   */
+  double GetVoltage() const;
+
+  /**
+   * Get a scaled sample from the output of the oversample and average engine
+   * for this channel.
+   *
+   * The value is scaled to units of Volts using the calibrated scaling data
+   * from GetLSBWeight() and GetOffset().
+   *
+   * Using oversampling will cause this value to be higher resolution, but it
+   * will update more slowly.
+   *
+   * Using averaging will cause this value to be more stable, but it will update
+   * more slowly.
+   *
+   * @return A scaled sample from the output of the oversample and average
+   * engine for this channel.
+   */
+  double GetAverageVoltage() const;
+
+  /**
+   * Get the channel number.
+   *
+   * @return The channel number.
+   */
+  int GetChannel() const;
+
+  /**
+   * Set the number of averaging bits.
+   *
+   * This sets the number of averaging bits. The actual number of averaged
+   * samples is 2^bits.
+   *
+   * Use averaging to improve the stability of your measurement at the expense
+   * of sampling rate. The averaging is done automatically in the FPGA.
+   *
+   * @param bits Number of bits of averaging.
+   */
+  void SetAverageBits(int bits);
+
+  /**
+   * Get the number of averaging bits previously configured.
+   *
+   * This gets the number of averaging bits from the FPGA. The actual number of
+   * averaged samples is 2^bits. The averaging is done automatically in the
+   * FPGA.
+   *
+   * @return Number of bits of averaging previously configured.
+   */
+  int GetAverageBits() const;
+
+  /**
+   * Set the number of oversample bits.
+   *
+   * This sets the number of oversample bits. The actual number of oversampled
+   * values is 2^bits. Use oversampling to improve the resolution of your
+   * measurements at the expense of sampling rate. The oversampling is done
+   * automatically in the FPGA.
+   *
+   * @param bits Number of bits of oversampling.
+   */
+  void SetOversampleBits(int bits);
+
+  /**
+   * Get the number of oversample bits previously configured.
+   *
+   * This gets the number of oversample bits from the FPGA. The actual number of
+   * oversampled values is 2^bits. The oversampling is done automatically in the
+   * FPGA.
+   *
+   * @return Number of bits of oversampling previously configured.
+   */
+  int GetOversampleBits() const;
+
+  /**
+   * Get the factory scaling least significant bit weight constant.
+   *
+   * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+   *
+   * @return Least significant bit weight.
+   */
+  int GetLSBWeight() const;
+
+  /**
+   * Get the factory scaling offset constant.
+   *
+   * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+   *
+   * @return Offset constant.
+   */
+  int GetOffset() const;
+
+  /**
+   * Is the channel attached to an accumulator.
+   *
+   * @return The analog input is attached to an accumulator.
+   */
+  bool IsAccumulatorChannel() const;
+
+  /**
+   * Initialize the accumulator.
+   */
+  void InitAccumulator();
+
+  /**
+   * Set an initial value for the accumulator.
+   *
+   * This will be added to all values returned to the user.
+   *
+   * @param initialValue The value that the accumulator should start from when
+   *                     reset.
+   */
+  void SetAccumulatorInitialValue(int64_t value);
+
+  /**
+   * Resets the accumulator to the initial value.
+   */
+  void ResetAccumulator();
+
+  /**
+   * Set the center value of the accumulator.
+   *
+   * The center value is subtracted from each A/D value before it is added to
+   * the accumulator. This is used for the center value of devices like gyros
+   * and accelerometers to take the device offset into account when integrating.
+   *
+   * This center value is based on the output of the oversampled and averaged
+   * source from the accumulator channel. Because of this, any non-zero
+   * oversample bits will affect the size of the value for this field.
+   */
+  void SetAccumulatorCenter(int center);
+
+  /**
+   * Set the accumulator's deadband.
+   */
+  void SetAccumulatorDeadband(int deadband);
+
+  /**
+   * Read the accumulated value.
+   *
+   * Read the value that has been accumulating.
+   * The accumulator is attached after the oversample and average engine.
+   *
+   * @return The 64-bit value accumulated since the last Reset().
+   */
+  int64_t GetAccumulatorValue() const;
+
+  /**
+   * Read the number of accumulated values.
+   *
+   * Read the count of the accumulated values since the accumulator was last
+   * Reset().
+   *
+   * @return The number of times samples from the channel were accumulated.
+   */
+  int64_t GetAccumulatorCount() const;
+
+  /**
+   * Read the accumulated value and the number of accumulated values atomically.
+   *
+   * This function reads the value and count from the FPGA atomically.
+   * This can be used for averaging.
+   *
+   * @param value Reference to the 64-bit accumulated output.
+   * @param count Reference to the number of accumulation cycles.
+   */
+  void GetAccumulatorOutput(int64_t& value, int64_t& count) const;
+
+  /**
+   * Set the sample rate per channel for all analog channels.
+   *
+   * The maximum rate is 500kS/s divided by the number of channels in use.
+   * This is 62500 samples/s per channel.
+   *
+   * @param samplesPerSecond The number of samples per second.
+   */
+  static void SetSampleRate(double samplesPerSecond);
+
+  /**
+   * Get the current sample rate for all channels
+   *
+   * @return Sample rate.
+   */
+  static double GetSampleRate();
+
+  /**
+   * Get the Average value for the PID Source base object.
+   *
+   * @return The average voltage.
+   */
+  double PIDGet() override;
+
+  /**
+   * Indicates this input is used by a simulated device.
+   *
+   * @param device simulated device handle
+   */
+  void SetSimDevice(HAL_SimDeviceHandle device);
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  int m_channel;
+  hal::Handle<HAL_AnalogInputHandle> m_port;
+  int64_t m_accumulatorOffset;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/AnalogOutput.h b/wpilibc/src/main/native/include/frc/AnalogOutput.h
new file mode 100644
index 0000000..1cecd70
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/AnalogOutput.h
@@ -0,0 +1,67 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+
+/**
+ * MXP analog output class.
+ */
+class AnalogOutput : public ErrorBase,
+                     public Sendable,
+                     public SendableHelper<AnalogOutput> {
+ public:
+  /**
+   * Construct an analog output on the given channel.
+   *
+   * All analog outputs are located on the MXP port.
+   *
+   * @param channel The channel number on the roboRIO to represent.
+   */
+  explicit AnalogOutput(int channel);
+
+  ~AnalogOutput() override;
+
+  AnalogOutput(AnalogOutput&&) = default;
+  AnalogOutput& operator=(AnalogOutput&&) = default;
+
+  /**
+   * Set the value of the analog output.
+   *
+   * @param voltage The output value in Volts, from 0.0 to +5.0
+   */
+  void SetVoltage(double voltage);
+
+  /**
+   * Get the voltage of the analog output
+   *
+   * @return The value in Volts, from 0.0 to +5.0
+   */
+  double GetVoltage() const;
+
+  /**
+   * Get the channel of this AnalogOutput.
+   */
+  int GetChannel();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ protected:
+  int m_channel;
+  hal::Handle<HAL_AnalogOutputHandle> m_port;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/AnalogPotentiometer.h b/wpilibc/src/main/native/include/frc/AnalogPotentiometer.h
new file mode 100644
index 0000000..446a920
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/AnalogPotentiometer.h
@@ -0,0 +1,126 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include "frc/AnalogInput.h"
+#include "frc/ErrorBase.h"
+#include "frc/interfaces/Potentiometer.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+
+/**
+ * Class for reading analog potentiometers. Analog potentiometers read in an
+ * analog voltage that corresponds to a position. The position is in whichever
+ * units you choose, by way of the scaling and offset constants passed to the
+ * constructor.
+ */
+class AnalogPotentiometer : public ErrorBase,
+                            public Potentiometer,
+                            public Sendable,
+                            public SendableHelper<AnalogPotentiometer> {
+ public:
+  /**
+   * Construct an Analog Potentiometer object from a channel number.
+   *
+   * Use the fullRange and offset values so that the output produces meaningful
+   * values. I.E: you have a 270 degree potentiometer and you want the output to
+   * be degrees with the halfway point as 0 degrees. The fullRange value is
+   * 270.0 degrees and the offset is -135.0 since the halfway point after
+   * scaling is 135 degrees.
+   *
+   * This will calculate the result from the fullRange times the fraction of the
+   * supply voltage, plus the offset.
+   *
+   * @param channel   The channel number on the roboRIO to represent. 0-3 are
+   *                  on-board 4-7 are on the MXP port.
+   * @param fullRange The angular value (in desired units) representing the full
+   *                  0-5V range of the input.
+   * @param offset    The angular value (in desired units) representing the
+   *                  angular output at 0V.
+   */
+  explicit AnalogPotentiometer(int channel, double fullRange = 1.0,
+                               double offset = 0.0);
+
+  /**
+   * Construct an Analog Potentiometer object from an existing Analog Input
+   * pointer.
+   *
+   * Use the fullRange and offset values so that the output produces meaningful
+   * values. I.E: you have a 270 degree potentiometer and you want the output to
+   * be degrees with the halfway point as 0 degrees. The fullRange value is
+   * 270.0 degrees and the offset is -135.0 since the halfway point after
+   * scaling is 135 degrees.
+   *
+   * This will calculate the result from the fullRange times the fraction of the
+   * supply voltage, plus the offset.
+   *
+   * @param channel   The existing Analog Input pointer
+   * @param fullRange The angular value (in desired units) representing the full
+   *                  0-5V range of the input.
+   * @param offset    The angular value (in desired units) representing the
+   *                  angular output at 0V.
+   */
+  explicit AnalogPotentiometer(AnalogInput* input, double fullRange = 1.0,
+                               double offset = 0.0);
+
+  /**
+   * Construct an Analog Potentiometer object from an existing Analog Input
+   * pointer.
+   *
+   * Use the fullRange and offset values so that the output produces meaningful
+   * values. I.E: you have a 270 degree potentiometer and you want the output to
+   * be degrees with the halfway point as 0 degrees. The fullRange value is
+   * 270.0 degrees and the offset is -135.0 since the halfway point after
+   * scaling is 135 degrees.
+   *
+   * This will calculate the result from the fullRange times the fraction of the
+   * supply voltage, plus the offset.
+   *
+   * @param channel   The existing Analog Input pointer
+   * @param fullRange The angular value (in desired units) representing the full
+   *                  0-5V range of the input.
+   * @param offset    The angular value (in desired units) representing the
+   *                  angular output at 0V.
+   */
+  explicit AnalogPotentiometer(std::shared_ptr<AnalogInput> input,
+                               double fullRange = 1.0, double offset = 0.0);
+
+  ~AnalogPotentiometer() override = default;
+
+  AnalogPotentiometer(AnalogPotentiometer&&) = default;
+  AnalogPotentiometer& operator=(AnalogPotentiometer&&) = default;
+
+  /**
+   * Get the current reading of the potentiomer.
+   *
+   * @return The current position of the potentiometer (in the units used for
+   *         fullRange and offset).
+   */
+  double Get() const override;
+
+  /**
+   * Implement the PIDSource interface.
+   *
+   * @return The current reading.
+   */
+  double PIDGet() override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  std::shared_ptr<AnalogInput> m_analog_input;
+  double m_fullRange, m_offset;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/AnalogTrigger.h b/wpilibc/src/main/native/include/frc/AnalogTrigger.h
new file mode 100644
index 0000000..7554bd9
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/AnalogTrigger.h
@@ -0,0 +1,177 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <hal/Types.h>
+
+#include "frc/AnalogTriggerOutput.h"
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class AnalogInput;
+class DutyCycle;
+class SendableBuilder;
+
+class AnalogTrigger : public ErrorBase,
+                      public Sendable,
+                      public SendableHelper<AnalogTrigger> {
+  friend class AnalogTriggerOutput;
+
+ public:
+  /**
+   * Constructor for an analog trigger given a channel number.
+   *
+   * @param channel The channel number on the roboRIO to represent. 0-3 are
+   *                on-board 4-7 are on the MXP port.
+   */
+  explicit AnalogTrigger(int channel);
+
+  /**
+   * Construct an analog trigger given an analog input.
+   *
+   * This should be used in the case of sharing an analog channel between the
+   * trigger and an analog input object.
+   *
+   * @param channel The pointer to the existing AnalogInput object
+   */
+  explicit AnalogTrigger(AnalogInput* channel);
+
+  /**
+   * Construct an analog trigger given a duty cycle input.
+   *
+   * @param channel The pointer to the existing DutyCycle object
+   */
+  explicit AnalogTrigger(DutyCycle* dutyCycle);
+
+  ~AnalogTrigger() override;
+
+  AnalogTrigger(AnalogTrigger&& rhs);
+  AnalogTrigger& operator=(AnalogTrigger&& rhs);
+
+  /**
+   * Set the upper and lower limits of the analog trigger.
+   *
+   * The limits are given as floating point voltage values.
+   *
+   * @param lower The lower limit of the trigger in Volts.
+   * @param upper The upper limit of the trigger in Volts.
+   */
+  void SetLimitsVoltage(double lower, double upper);
+
+  /**
+   * Set the upper and lower duty cycle limits of the analog trigger.
+   *
+   * The limits are given as floating point values between 0 and 1.
+   *
+   * @param lower The lower limit of the trigger in percentage.
+   * @param upper The upper limit of the trigger in percentage.
+   */
+  void SetLimitsDutyCycle(double lower, double upper);
+
+  /**
+   * Set the upper and lower limits of the analog trigger.
+   *
+   * The limits are given in ADC codes.  If oversampling is used, the units must
+   * be scaled appropriately.
+   *
+   * @param lower The lower limit of the trigger in ADC codes (12-bit values).
+   * @param upper The upper limit of the trigger in ADC codes (12-bit values).
+   */
+  void SetLimitsRaw(int lower, int upper);
+
+  /**
+   * Configure the analog trigger to use the averaged vs. raw values.
+   *
+   * If the value is true, then the averaged value is selected for the analog
+   * trigger, otherwise the immediate value is used.
+   *
+   * @param useAveragedValue If true, use the Averaged value, otherwise use the
+   *                         instantaneous reading
+   */
+  void SetAveraged(bool useAveragedValue);
+
+  /**
+   * Configure the analog trigger to use the duty cycle vs. raw values.
+   *
+   * If the value is true, then the duty cycle value is selected for the analog
+   * trigger, otherwise the immediate value is used.
+   *
+   * @param useDutyCycle If true, use the duty cycle value, otherwise use the
+   *                         instantaneous reading
+   */
+  void SetDutyCycle(bool useDutyCycle);
+
+  /**
+   * Configure the analog trigger to use a filtered value.
+   *
+   * The analog trigger will operate with a 3 point average rejection filter.
+   * This is designed to help with 360 degree pot applications for the period
+   * where the pot crosses through zero.
+   *
+   * @param useFilteredValue If true, use the 3 point rejection filter,
+   *                         otherwise use the unfiltered value
+   */
+  void SetFiltered(bool useFilteredValue);
+
+  /**
+   * Return the index of the analog trigger.
+   *
+   * This is the FPGA index of this analog trigger instance.
+   *
+   * @return The index of the analog trigger.
+   */
+  int GetIndex() const;
+
+  /**
+   * Return the InWindow output of the analog trigger.
+   *
+   * True if the analog input is between the upper and lower limits.
+   *
+   * @return True if the analog input is between the upper and lower limits.
+   */
+  bool GetInWindow();
+
+  /**
+   * Return the TriggerState output of the analog trigger.
+   *
+   * True if above upper limit.
+   * False if below lower limit.
+   * If in Hysteresis, maintain previous state.
+   *
+   * @return True if above upper limit. False if below lower limit. If in
+   *         Hysteresis, maintain previous state.
+   */
+  bool GetTriggerState();
+
+  /**
+   * Creates an AnalogTriggerOutput object.
+   *
+   * Gets an output object that can be used for routing. Caller is responsible
+   * for deleting the AnalogTriggerOutput object.
+   *
+   * @param type An enum of the type of output object to create.
+   * @return A pointer to a new AnalogTriggerOutput object.
+   */
+  std::shared_ptr<AnalogTriggerOutput> CreateOutput(
+      AnalogTriggerType type) const;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  hal::Handle<HAL_AnalogTriggerHandle> m_trigger;
+  AnalogInput* m_analogInput = nullptr;
+  DutyCycle* m_dutyCycle = nullptr;
+  bool m_ownsAnalog = false;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/AnalogTriggerOutput.h b/wpilibc/src/main/native/include/frc/AnalogTriggerOutput.h
new file mode 100644
index 0000000..989a93f
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/AnalogTriggerOutput.h
@@ -0,0 +1,108 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/DigitalSource.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class AnalogTrigger;
+
+/**
+ * Class to represent a specific output from an analog trigger.
+ *
+ * This class is used to get the current output value and also as a
+ * DigitalSource to provide routing of an output to digital subsystems on the
+ * FPGA such as Counter, Encoder, and Interrupt.
+ *
+ * The TriggerState output indicates the primary output value of the trigger.
+ * If the analog signal is less than the lower limit, the output is false. If
+ * the analog value is greater than the upper limit, then the output is true.
+ * If the analog value is in between, then the trigger output state maintains
+ * its most recent value.
+ *
+ * The InWindow output indicates whether or not the analog signal is inside the
+ * range defined by the limits.
+ *
+ * The RisingPulse and FallingPulse outputs detect an instantaneous transition
+ * from above the upper limit to below the lower limit, and vise versa. These
+ * pulses represent a rollover condition of a sensor and can be routed to an up
+ * / down counter or to interrupts. Because the outputs generate a pulse, they
+ * cannot be read directly. To help ensure that a rollover condition is not
+ * missed, there is an average rejection filter available that operates on the
+ * upper 8 bits of a 12 bit number and selects the nearest outlyer of 3 samples.
+ * This will reject a sample that is (due to averaging or sampling) errantly
+ * between the two limits. This filter will fail if more than one sample in a
+ * row is errantly in between the two limits. You may see this problem if
+ * attempting to use this feature with a mechanical rollover sensor, such as a
+ * 360 degree no-stop potentiometer without signal conditioning, because the
+ * rollover transition is not sharp / clean enough. Using the averaging engine
+ * may help with this, but rotational speeds of the sensor will then be limited.
+ */
+class AnalogTriggerOutput : public DigitalSource,
+                            public Sendable,
+                            public SendableHelper<AnalogTriggerOutput> {
+  friend class AnalogTrigger;
+
+ public:
+  /**
+   * Get the state of the analog trigger output.
+   *
+   * @return The state of the analog trigger output.
+   */
+  bool Get() const;
+
+  // DigitalSource interface
+  /**
+   * @return The HAL Handle to the specified source.
+   */
+  HAL_Handle GetPortHandleForRouting() const override;
+
+  /**
+   * @return The type of analog trigger output to be used.
+   */
+  AnalogTriggerType GetAnalogTriggerTypeForRouting() const override;
+
+  /**
+   * Is source an AnalogTrigger
+   */
+  bool IsAnalogTrigger() const override;
+
+  /**
+   * @return The channel of the source.
+   */
+  int GetChannel() const override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ protected:
+  /**
+   * Create an object that represents one of the four outputs from an analog
+   * trigger.
+   *
+   * Because this class derives from DigitalSource, it can be passed into
+   * routing functions for Counter, Encoder, etc.
+   *
+   * @param trigger    A pointer to the trigger for which this is an output.
+   * @param outputType An enum that specifies the output on the trigger to
+   *                   represent.
+   */
+  AnalogTriggerOutput(const AnalogTrigger& trigger,
+                      AnalogTriggerType outputType);
+
+ private:
+  // Uses pointer rather than smart pointer because a user can not construct
+  // an AnalogTriggerOutput themselves and because the AnalogTriggerOutput
+  // should always be in scope at the same time as an AnalogTrigger.
+  const AnalogTrigger* m_trigger;
+  AnalogTriggerType m_outputType;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/AnalogTriggerType.h b/wpilibc/src/main/native/include/frc/AnalogTriggerType.h
new file mode 100644
index 0000000..f15fb03
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/AnalogTriggerType.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+enum class AnalogTriggerType {
+  kInWindow = 0,
+  kState = 1,
+  kRisingPulse = 2,
+  kFallingPulse = 3
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Base.h b/wpilibc/src/main/native/include/frc/Base.h
new file mode 100644
index 0000000..1fdbe5d
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Base.h
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#if !defined(__clang__) && defined(__GNUC__) && __GNUC__ < 5
+static_assert(0,
+              "GCC must be 5 or greater. If building for the roboRIO, please "
+              "update to the 2018 toolchains.");
+#endif
+
+#if defined(_MSC_VER) && _MSC_VER < 1900
+static_assert(0, "Visual Studio 2015 or greater required.");
+#endif
+
+/** WPILib FRC namespace */
+namespace frc {
+
+// A struct to use as a deleter when a std::shared_ptr must wrap a raw pointer
+// that is being deleted by someone else.
+template <class T>
+struct NullDeleter {
+  void operator()(T*) const noexcept {};
+};
+
+}  // namespace frc
+
+// For backwards compatibility
+#ifdef NO_NAMESPACED_WPILIB
+using namespace frc;  // NOLINT
+#endif
diff --git a/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h b/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h
new file mode 100644
index 0000000..8148e72
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h
@@ -0,0 +1,67 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/ErrorBase.h"
+#include "frc/interfaces/Accelerometer.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+
+/**
+ * Built-in accelerometer.
+ *
+ * This class allows access to the roboRIO's internal accelerometer.
+ */
+class BuiltInAccelerometer : public ErrorBase,
+                             public Accelerometer,
+                             public Sendable,
+                             public SendableHelper<BuiltInAccelerometer> {
+ public:
+  /**
+   * Constructor.
+   *
+   * @param range The range the accelerometer will measure
+   */
+  explicit BuiltInAccelerometer(Range range = kRange_8G);
+
+  BuiltInAccelerometer(BuiltInAccelerometer&&) = default;
+  BuiltInAccelerometer& operator=(BuiltInAccelerometer&&) = default;
+
+  // Accelerometer interface
+  /**
+   * Set the measuring range of the accelerometer.
+   *
+   * @param range The maximum acceleration, positive or negative, that the
+   *              accelerometer will measure. Not all accelerometers support all
+   *              ranges.
+   */
+  void SetRange(Range range) override;
+
+  /**
+   * @return The acceleration of the roboRIO along the X axis in g-forces
+   */
+  double GetX() override;
+
+  /**
+   * @return The acceleration of the roboRIO along the Y axis in g-forces
+   */
+  double GetY() override;
+
+  /**
+   * @return The acceleration of the roboRIO along the Z axis in g-forces
+   */
+  double GetZ() override;
+
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/CAN.h b/wpilibc/src/main/native/include/frc/CAN.h
new file mode 100644
index 0000000..ed861fb
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/CAN.h
@@ -0,0 +1,142 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <hal/CANAPITypes.h>
+#include <wpi/ArrayRef.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+struct CANData {
+  uint8_t data[8];
+  int32_t length;
+  uint64_t timestamp;
+};
+
+/**
+ * High level class for interfacing with CAN devices conforming to
+ * the standard CAN spec.
+ *
+ * No packets that can be sent gets blocked by the RoboRIO, so all methods
+ * work identically in all robot modes.
+ *
+ * All methods are thread save, however the buffer objects passed in
+ * by the user need to not be modified for the duration of their calls.
+ */
+class CAN : public ErrorBase {
+ public:
+  /**
+   * Create a new CAN communication interface with the specific device ID.
+   * This uses the team manufacturer and device types.
+   * The device ID is 6 bits (0-63)
+   *
+   * @param deviceId The device id
+   */
+  explicit CAN(int deviceId);
+
+  /**
+   * Create a new CAN communication interface with a specific device ID,
+   * manufacturer and device type. The device ID is 6 bits, the
+   * manufacturer is 8 bits, and the device type is 5 bits.
+   *
+   * @param deviceId           The device ID
+   * @param deviceManufacturer The device manufacturer
+   * @param deviceType         The device type
+   */
+  CAN(int deviceId, int deviceManufacturer, int deviceType);
+
+  /**
+   * Closes the CAN communication.
+   */
+  ~CAN() override;
+
+  CAN(CAN&&) = default;
+  CAN& operator=(CAN&&) = default;
+
+  /**
+   * Write a packet to the CAN device with a specific ID. This ID is 10 bits.
+   *
+   * @param data The data to write (8 bytes max)
+   * @param length The data length to write
+   * @param apiId The API ID to write.
+   */
+  void WritePacket(const uint8_t* data, int length, int apiId);
+
+  /**
+   * Write a repeating packet to the CAN device with a specific ID. This ID is
+   * 10 bits. The RoboRIO will automatically repeat the packet at the specified
+   * interval
+   *
+   * @param data The data to write (8 bytes max)
+   * @param length The data length to write
+   * @param apiId The API ID to write.
+   * @param repeatMs The period to repeat the packet at.
+   */
+  void WritePacketRepeating(const uint8_t* data, int length, int apiId,
+                            int repeatMs);
+
+  /**
+   * Write an RTR frame to the CAN device with a specific ID. This ID is 10
+   * bits. The length by spec must match what is returned by the responding
+   * device
+   *
+   * @param length The length to request (0 to 8)
+   * @param apiId The API ID to write.
+   */
+  void WriteRTRFrame(int length, int apiId);
+
+  /**
+   * Stop a repeating packet with a specific ID. This ID is 10 bits.
+   *
+   * @param apiId The API ID to stop repeating
+   */
+  void StopPacketRepeating(int apiId);
+
+  /**
+   * Read a new CAN packet. This will only return properly once per packet
+   * received. Multiple calls without receiving another packet will return
+   * false.
+   *
+   * @param apiId The API ID to read.
+   * @param data Storage for the received data.
+   * @return True if the data is valid, otherwise false.
+   */
+  bool ReadPacketNew(int apiId, CANData* data);
+
+  /**
+   * Read a CAN packet. The will continuously return the last packet received,
+   * without accounting for packet age.
+   *
+   * @param apiId The API ID to read.
+   * @param data Storage for the received data.
+   * @return True if the data is valid, otherwise false.
+   */
+  bool ReadPacketLatest(int apiId, CANData* data);
+
+  /**
+   * Read a CAN packet. The will return the last packet received until the
+   * packet is older then the requested timeout. Then it will return false.
+   *
+   * @param apiId The API ID to read.
+   * @param timeoutMs The timeout time for the packet
+   * @param data Storage for the received data.
+   * @return True if the data is valid, otherwise false.
+   */
+  bool ReadPacketTimeout(int apiId, int timeoutMs, CANData* data);
+
+  static constexpr HAL_CANManufacturer kTeamManufacturer = HAL_CAN_Man_kTeamUse;
+  static constexpr HAL_CANDeviceType kTeamDeviceType =
+      HAL_CAN_Dev_kMiscellaneous;
+
+ private:
+  hal::Handle<HAL_CANHandle> m_handle;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Compressor.h b/wpilibc/src/main/native/include/frc/Compressor.h
new file mode 100644
index 0000000..a5e512c
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Compressor.h
@@ -0,0 +1,184 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/SensorUtil.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+
+/**
+ * Class for operating a compressor connected to a %PCM (Pneumatic Control
+ * Module).
+ *
+ * The PCM will automatically run in closed loop mode by default whenever a
+ * Solenoid object is created. For most cases, a Compressor object does not need
+ * to be instantiated or used in a robot program. This class is only required in
+ * cases where the robot program needs a more detailed status of the compressor
+ * or to enable/disable closed loop control.
+ *
+ * Note: you cannot operate the compressor directly from this class as doing so
+ * would circumvent the safety provided by using the pressure switch and closed
+ * loop control. You can only turn off closed loop control, thereby stopping
+ * the compressor from operating.
+ */
+class Compressor : public ErrorBase,
+                   public Sendable,
+                   public SendableHelper<Compressor> {
+ public:
+  /**
+   * Constructor. The default PCM ID is 0.
+   *
+   * @param module The PCM ID to use (0-62)
+   */
+  explicit Compressor(int pcmID = SensorUtil::GetDefaultSolenoidModule());
+
+  ~Compressor() override = default;
+
+  Compressor(Compressor&&) = default;
+  Compressor& operator=(Compressor&&) = default;
+
+  /**
+   * Starts closed-loop control. Note that closed loop control is enabled by
+   * default.
+   */
+  void Start();
+
+  /**
+   * Stops closed-loop control. Note that closed loop control is enabled by
+   * default.
+   */
+  void Stop();
+
+  /**
+   * Check if compressor output is active.
+   *
+   * @return true if the compressor is on
+   */
+  bool Enabled() const;
+
+  /**
+   * Check if the pressure switch is triggered.
+   *
+   * @return true if pressure is low
+   */
+  bool GetPressureSwitchValue() const;
+
+  /**
+   * Query how much current the compressor is drawing.
+   *
+   * @return The current through the compressor, in amps
+   */
+  double GetCompressorCurrent() const;
+
+  /**
+   * Enables or disables automatically turning the compressor on when the
+   * pressure is low.
+   *
+   * @param on Set to true to enable closed loop control of the compressor.
+   *           False to disable.
+   */
+  void SetClosedLoopControl(bool on);
+
+  /**
+   * Returns true if the compressor will automatically turn on when the
+   * pressure is low.
+   *
+   * @return True if closed loop control of the compressor is enabled. False if
+   *         disabled.
+   */
+  bool GetClosedLoopControl() const;
+
+  /**
+   * Query if the compressor output has been disabled due to high current draw.
+   *
+   * @return true if PCM is in fault state : Compressor Drive is
+   *         disabled due to compressor current being too high.
+   */
+  bool GetCompressorCurrentTooHighFault() const;
+
+  /**
+   * Query if the compressor output has been disabled due to high current draw
+   * (sticky).
+   *
+   * A sticky fault will not clear on device reboot, it must be cleared through
+   * code or the webdash.
+   *
+   * @return true if PCM sticky fault is set : Compressor Drive is
+   *         disabled due to compressor current being too high.
+   */
+  bool GetCompressorCurrentTooHighStickyFault() const;
+
+  /**
+   * Query if the compressor output has been disabled due to a short circuit
+   * (sticky).
+   *
+   * A sticky fault will not clear on device reboot, it must be cleared through
+   * code or the webdash.
+   *
+   * @return true if PCM sticky fault is set : Compressor output
+   *         appears to be shorted.
+   */
+  bool GetCompressorShortedStickyFault() const;
+
+  /**
+   * Query if the compressor output has been disabled due to a short circuit.
+   *
+   * @return true if PCM is in fault state : Compressor output
+   *         appears to be shorted.
+   */
+  bool GetCompressorShortedFault() const;
+
+  /**
+   * Query if the compressor output does not appear to be wired (sticky).
+   *
+   * A sticky fault will not clear on device reboot, it must be cleared through
+   * code or the webdash.
+   *
+   * @return true if PCM sticky fault is set : Compressor does not
+   *         appear to be wired, i.e. compressor is not drawing enough current.
+   */
+  bool GetCompressorNotConnectedStickyFault() const;
+
+  /**
+   * Query if the compressor output does not appear to be wired.
+   *
+   * @return true if PCM is in fault state : Compressor does not
+   *         appear to be wired, i.e. compressor is not drawing enough current.
+   */
+  bool GetCompressorNotConnectedFault() const;
+
+  /**
+   * Clear ALL sticky faults inside PCM that Compressor is wired to.
+   *
+   * If a sticky fault is set, then it will be persistently cleared.  Compressor
+   * drive maybe momentarily disable while flags are being cleared. Care should
+   * be taken to not call this too frequently, otherwise normal compressor
+   * functionality may be prevented.
+   *
+   * If no sticky faults are set then this call will have no effect.
+   */
+  void ClearAllPCMStickyFaults();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ protected:
+  hal::Handle<HAL_CompressorHandle> m_compressorHandle;
+
+ private:
+  void SetCompressor(bool on);
+  int m_module;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Controller.h b/wpilibc/src/main/native/include/frc/Controller.h
new file mode 100644
index 0000000..4124046
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Controller.h
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/deprecated.h>
+
+namespace frc {
+
+/**
+ * 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:
+  WPI_DEPRECATED("None of the 2020 FRC controllers use this.")
+  Controller() = default;
+  virtual ~Controller() = default;
+
+  Controller(Controller&&) = default;
+  Controller& operator=(Controller&&) = default;
+
+  /**
+   * Allows the control loop to run
+   */
+  virtual void Enable() = 0;
+
+  /**
+   * Stops the control loop from running until explicitly re-enabled by calling
+   * enable()
+   */
+  virtual void Disable() = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Counter.h b/wpilibc/src/main/native/include/frc/Counter.h
new file mode 100644
index 0000000..2770a02
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Counter.h
@@ -0,0 +1,446 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <hal/Types.h>
+
+#include "frc/AnalogTrigger.h"
+#include "frc/CounterBase.h"
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class DigitalGlitchFilter;
+class SendableBuilder;
+class DMA;
+class DMASample;
+
+/**
+ * Class for counting the number of ticks on a digital input channel.
+ *
+ * This is a general purpose class for counting repetitive events. It can return
+ * the number of counts, the period of the most recent cycle, and detect when
+ * the signal being counted has stopped by supplying a maximum cycle time.
+ *
+ * All counters will immediately start counting - Reset() them if you need them
+ * to be zeroed before use.
+ */
+class Counter : public ErrorBase,
+                public CounterBase,
+                public Sendable,
+                public SendableHelper<Counter> {
+  friend class DMA;
+  friend class DMASample;
+
+ public:
+  enum Mode {
+    kTwoPulse = 0,
+    kSemiperiod = 1,
+    kPulseLength = 2,
+    kExternalDirection = 3
+  };
+
+  /**
+   * Create an instance of a counter where no sources are selected.
+   *
+   * They all must be selected by calling functions to specify the upsource and
+   * the downsource independently.
+   *
+   * This creates a ChipObject counter and initializes status variables
+   * appropriately.
+   *
+   * The counter will start counting immediately.
+   *
+   * @param mode The counter mode
+   */
+  explicit Counter(Mode mode = kTwoPulse);
+
+  /**
+   * Create an instance of a Counter object.
+   *
+   * Create an up-Counter instance given a channel.
+   *
+   * The counter will start counting immediately.
+   *
+   * @param channel The DIO channel to use as the up source. 0-9 are on-board,
+   *                10-25 are on the MXP
+   */
+  explicit Counter(int channel);
+
+  /**
+   * Create an instance of a counter from a Digital Source (such as a Digital
+   * Input).
+   *
+   * This is used if an existing digital input is to be shared by multiple other
+   * objects such as encoders or if the Digital Source is not a Digital Input
+   * channel (such as an Analog Trigger).
+   *
+   * The counter will start counting immediately.
+   * @param source A pointer to the existing DigitalSource object. It will be
+   *               set as the Up Source.
+   */
+  explicit Counter(DigitalSource* source);
+
+  /**
+   * Create an instance of a counter from a Digital Source (such as a Digital
+   * Input).
+   *
+   * This is used if an existing digital input is to be shared by multiple other
+   * objects such as encoders or if the Digital Source is not a Digital Input
+   * channel (such as an Analog Trigger).
+   *
+   * The counter will start counting immediately.
+   *
+   * @param source A pointer to the existing DigitalSource object. It will be
+   *               set as the Up Source.
+   */
+  explicit Counter(std::shared_ptr<DigitalSource> source);
+
+  /**
+   * Create an instance of a Counter object.
+   *
+   * Create an instance of a simple up-Counter given an analog trigger.
+   * Use the trigger state output from the analog trigger.
+   *
+   * The counter will start counting immediately.
+   *
+   * @param trigger The reference to the existing AnalogTrigger object.
+   */
+  explicit Counter(const AnalogTrigger& trigger);
+
+  /**
+   * Create an instance of a Counter object.
+   *
+   * Creates a full up-down counter given two Digital Sources.
+   *
+   * @param encodingType The quadrature decoding mode (1x or 2x)
+   * @param upSource     The pointer to the DigitalSource to set as the up
+   *                     source
+   * @param downSource   The pointer to the DigitalSource to set as the down
+   *                     source
+   * @param inverted     True to invert the output (reverse the direction)
+   */
+  Counter(EncodingType encodingType, DigitalSource* upSource,
+          DigitalSource* downSource, bool inverted);
+
+  /**
+   * Create an instance of a Counter object.
+   *
+   * Creates a full up-down counter given two Digital Sources.
+   *
+   * @param encodingType The quadrature decoding mode (1x or 2x)
+   * @param upSource     The pointer to the DigitalSource to set as the up
+   *                     source
+   * @param downSource   The pointer to the DigitalSource to set as the down
+   *                     source
+   * @param inverted     True to invert the output (reverse the direction)
+   */
+  Counter(EncodingType encodingType, std::shared_ptr<DigitalSource> upSource,
+          std::shared_ptr<DigitalSource> downSource, bool inverted);
+
+  ~Counter() override;
+
+  Counter(Counter&&) = default;
+  Counter& operator=(Counter&&) = default;
+
+  /**
+   * Set the upsource for the counter as a digital input channel.
+   *
+   * @param channel The DIO channel to use as the up source. 0-9 are on-board,
+   *                10-25 are on the MXP
+   */
+  void SetUpSource(int channel);
+
+  /**
+   * Set the up counting source to be an analog trigger.
+   *
+   * @param analogTrigger The analog trigger object that is used for the Up
+   *                      Source
+   * @param triggerType   The analog trigger output that will trigger the
+   *                      counter.
+   */
+  void SetUpSource(AnalogTrigger* analogTrigger, AnalogTriggerType triggerType);
+
+  /**
+   * Set the up counting source to be an analog trigger.
+   *
+   * @param analogTrigger The analog trigger object that is used for the Up
+   *                      Source
+   * @param triggerType   The analog trigger output that will trigger the
+   *                      counter.
+   */
+  void SetUpSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                   AnalogTriggerType triggerType);
+
+  void SetUpSource(DigitalSource* source);
+
+  /**
+   * Set the source object that causes the counter to count up.
+   *
+   * Set the up counting DigitalSource.
+   *
+   * @param source Pointer to the DigitalSource object to set as the up source
+   */
+  void SetUpSource(std::shared_ptr<DigitalSource> source);
+
+  /**
+   * Set the source object that causes the counter to count up.
+   *
+   * Set the up counting DigitalSource.
+   *
+   * @param source Reference to the DigitalSource object to set as the up source
+   */
+  void SetUpSource(DigitalSource& source);
+
+  /**
+   * Set the edge sensitivity on an up counting source.
+   *
+   * Set the up source to either detect rising edges or falling edges or both.
+   *
+   * @param risingEdge  True to trigger on rising edges
+   * @param fallingEdge True to trigger on falling edges
+   */
+  void SetUpSourceEdge(bool risingEdge, bool fallingEdge);
+
+  /**
+   * Disable the up counting source to the counter.
+   */
+  void ClearUpSource();
+
+  /**
+   * Set the down counting source to be a digital input channel.
+   *
+   * @param channel The DIO channel to use as the up source. 0-9 are on-board,
+   *                10-25 are on the MXP
+   */
+  void SetDownSource(int channel);
+
+  /**
+   * Set the down counting source to be an analog trigger.
+   *
+   * @param analogTrigger The analog trigger object that is used for the Down
+   *                      Source
+   * @param triggerType   The analog trigger output that will trigger the
+   *                      counter.
+   */
+  void SetDownSource(AnalogTrigger* analogTrigger,
+                     AnalogTriggerType triggerType);
+
+  /**
+   * Set the down counting source to be an analog trigger.
+   *
+   * @param analogTrigger The analog trigger object that is used for the Down
+   *                      Source
+   * @param triggerType   The analog trigger output that will trigger the
+   *                      counter.
+   */
+  void SetDownSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                     AnalogTriggerType triggerType);
+
+  /**
+   * Set the source object that causes the counter to count down.
+   *
+   * Set the down counting DigitalSource.
+   *
+   * @param source Pointer to the DigitalSource object to set as the down source
+   */
+  void SetDownSource(DigitalSource* source);
+
+  /**
+   * Set the source object that causes the counter to count down.
+   *
+   * Set the down counting DigitalSource.
+   *
+   * @param source Reference to the DigitalSource object to set as the down
+   *               source
+   */
+  void SetDownSource(DigitalSource& source);
+
+  void SetDownSource(std::shared_ptr<DigitalSource> source);
+
+  /**
+   * Set the edge sensitivity on a down counting source.
+   *
+   * Set the down source to either detect rising edges or falling edges.
+   *
+   * @param risingEdge  True to trigger on rising edges
+   * @param fallingEdge True to trigger on falling edges
+   */
+  void SetDownSourceEdge(bool risingEdge, bool fallingEdge);
+
+  /**
+   * Disable the down counting source to the counter.
+   */
+  void ClearDownSource();
+
+  /**
+   * Set standard up / down counting mode on this counter.
+   *
+   * Up and down counts are sourced independently from two inputs.
+   */
+  void SetUpDownCounterMode();
+
+  /**
+   * Set external direction mode on this counter.
+   *
+   * Counts are sourced on the Up counter input.
+   * The Down counter input represents the direction to count.
+   */
+  void SetExternalDirectionMode();
+
+  /**
+   * Set Semi-period mode on this counter.
+   *
+   * Counts up on both rising and falling edges.
+   */
+  void SetSemiPeriodMode(bool highSemiPeriod);
+
+  /**
+   * Configure the counter to count in up or down based on the length of the
+   * input pulse.
+   *
+   * This mode is most useful for direction sensitive gear tooth sensors.
+   *
+   * @param threshold The pulse length beyond which the counter counts the
+   *                  opposite direction. Units are seconds.
+   */
+  void SetPulseLengthMode(double threshold);
+
+  /**
+   * Set the Counter to return reversed sensing on the direction.
+   *
+   * This allows counters to change the direction they are counting in the case
+   * of 1X and 2X quadrature encoding only. Any other counter mode isn't
+   * supported.
+   *
+   * @param reverseDirection true if the value counted should be negated.
+   */
+  void SetReverseDirection(bool reverseDirection);
+
+  /**
+   * Set the Samples to Average which specifies the number of samples of the
+   * timer to average when calculating the period. Perform averaging to account
+   * for mechanical imperfections or as oversampling to increase resolution.
+   *
+   * @param samplesToAverage The number of samples to average from 1 to 127.
+   */
+  void SetSamplesToAverage(int samplesToAverage);
+
+  /**
+   * Get the Samples to Average which specifies the number of samples of the
+   * timer to average when calculating the period.
+   *
+   * Perform averaging to account for mechanical imperfections or as
+   * oversampling to increase resolution.
+   *
+   * @return The number of samples being averaged (from 1 to 127)
+   */
+  int GetSamplesToAverage() const;
+
+  int GetFPGAIndex() const;
+
+  // CounterBase interface
+  /**
+   * Read the current counter value.
+   *
+   * Read the value at this instant. It may still be running, so it reflects the
+   * current value. Next time it is read, it might have a different value.
+   */
+  int Get() const override;
+
+  /**
+   * Reset the Counter to zero.
+   *
+   * Set the counter value to zero. This doesn't effect the running state of the
+   * counter, just sets the current value to zero.
+   */
+  void Reset() override;
+
+  /**
+   * Get the Period of the most recent count.
+   *
+   * Returns the time interval of the most recent count. This can be used for
+   * velocity calculations to determine shaft speed.
+   *
+   * @returns The period between the last two pulses in units of seconds.
+   */
+  double GetPeriod() const override;
+
+  /**
+   * Set the maximum period where the device is still considered "moving".
+   *
+   * Sets the maximum period where the device is considered moving. This value
+   * is used to determine the "stopped" state of the counter using the
+   * GetStopped method.
+   *
+   * @param maxPeriod The maximum period where the counted device is considered
+   *                  moving in seconds.
+   */
+  void SetMaxPeriod(double maxPeriod) override;
+
+  /**
+   * Select whether you want to continue updating the event timer output when
+   * there are no samples captured.
+   *
+   * The output of the event timer has a buffer of periods that are averaged and
+   * posted to a register on the FPGA.  When the timer detects that the event
+   * source has stopped (based on the MaxPeriod) the buffer of samples to be
+   * averaged is emptied.  If you enable the update when empty, you will be
+   * notified of the stopped source and the event time will report 0 samples.
+   * If you disable update when empty, the most recent average will remain on
+   * the output until a new sample is acquired.  You will never see 0 samples
+   * output (except when there have been no events since an FPGA reset) and you
+   * will likely not see the stopped bit become true (since it is updated at the
+   * end of an average and there are no samples to average).
+   *
+   * @param enabled True to enable update when empty
+   */
+  void SetUpdateWhenEmpty(bool enabled);
+
+  /**
+   * Determine if the clock is stopped.
+   *
+   * Determine if the clocked input is stopped based on the MaxPeriod value set
+   * using the SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the
+   * device (and counter) are assumed to be stopped and it returns true.
+   *
+   * @return Returns true if the most recent counter period exceeds the
+   *         MaxPeriod value set by SetMaxPeriod.
+   */
+  bool GetStopped() const override;
+
+  /**
+   * The last direction the counter value changed.
+   *
+   * @return The last direction the counter value changed.
+   */
+  bool GetDirection() const override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ protected:
+  // Makes the counter count up.
+  std::shared_ptr<DigitalSource> m_upSource;
+
+  // Makes the counter count down.
+  std::shared_ptr<DigitalSource> m_downSource;
+
+  // The FPGA counter object
+  hal::Handle<HAL_CounterHandle> m_counter;
+
+ private:
+  int m_index = 0;  // The index of this counter.
+
+  friend class DigitalGlitchFilter;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/CounterBase.h b/wpilibc/src/main/native/include/frc/CounterBase.h
new file mode 100644
index 0000000..7fde3ac
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/CounterBase.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+/**
+ * Interface for counting the number of ticks on a digital input channel.
+ *
+ * Encoders, Gear tooth sensors, and counters should all subclass this so it can
+ * be used to build more advanced classes for control and driving.
+ *
+ * All counters will immediately start counting - Reset() them if you need them
+ * to be zeroed before use.
+ */
+class CounterBase {
+ public:
+  enum EncodingType { k1X, k2X, k4X };
+
+  CounterBase() = default;
+  virtual ~CounterBase() = default;
+
+  CounterBase(CounterBase&&) = default;
+  CounterBase& operator=(CounterBase&&) = default;
+
+  virtual int Get() const = 0;
+  virtual void Reset() = 0;
+  virtual double GetPeriod() const = 0;
+  virtual void SetMaxPeriod(double maxPeriod) = 0;
+  virtual bool GetStopped() const = 0;
+  virtual bool GetDirection() const = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/DMA.h b/wpilibc/src/main/native/include/frc/DMA.h
new file mode 100644
index 0000000..57cdd27
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/DMA.h
@@ -0,0 +1,57 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+class Encoder;
+class Counter;
+class DigitalSource;
+class DutyCycle;
+class AnalogInput;
+class DMASample;
+
+class DMA : public ErrorBase {
+  friend class DMASample;
+
+ public:
+  DMA();
+  ~DMA() override;
+
+  DMA& operator=(DMA&& other) = default;
+  DMA(DMA&& other) = default;
+
+  void SetPause(bool pause);
+  void SetRate(int cycles);
+
+  void AddEncoder(const Encoder* encoder);
+  void AddEncoderPeriod(const Encoder* encoder);
+
+  void AddCounter(const Counter* counter);
+  void AddCounterPeriod(const Counter* counter);
+
+  void AddDigitalSource(const DigitalSource* digitalSource);
+
+  void AddDutyCycle(const DutyCycle* digitalSource);
+
+  void AddAnalogInput(const AnalogInput* analogInput);
+  void AddAveragedAnalogInput(const AnalogInput* analogInput);
+  void AddAnalogAccumulator(const AnalogInput* analogInput);
+
+  void SetExternalTrigger(DigitalSource* source, bool rising, bool falling);
+
+  void StartDMA(int queueDepth);
+  void StopDMA();
+
+ private:
+  hal::Handle<HAL_DMAHandle> dmaHandle;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/DMASample.h b/wpilibc/src/main/native/include/frc/DMASample.h
new file mode 100644
index 0000000..4592930
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/DMASample.h
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <type_traits>
+
+#include <hal/AnalogInput.h>
+#include <hal/DMA.h>
+#include <units/units.h>
+
+#include "frc/AnalogInput.h"
+#include "frc/Counter.h"
+#include "frc/DMA.h"
+#include "frc/DutyCycle.h"
+#include "frc/Encoder.h"
+
+namespace frc {
+class DMASample : public HAL_DMASample {
+ public:
+  HAL_DMAReadStatus Update(const DMA* dma, units::second_t timeout,
+                           int32_t* remaining, int32_t* status) {
+    units::millisecond_t ms = timeout;
+    auto timeoutMs = ms.to<int32_t>();
+    return HAL_ReadDMA(dma->dmaHandle, this, timeoutMs, remaining, status);
+  }
+
+  uint64_t GetTime() const { return timeStamp; }
+
+  units::second_t GetTimeStamp() const {
+    return units::second_t{static_cast<double>(GetTime()) * 1.0e-6};
+  }
+
+  int32_t GetEncoderRaw(const Encoder* encoder, int32_t* status) const {
+    return HAL_GetDMASampleEncoderRaw(this, encoder->m_encoder, status);
+  }
+
+  double GetEncoderDistance(const Encoder* encoder, int32_t* status) const {
+    double val = GetEncoderRaw(encoder, status);
+    val *= encoder->DecodingScaleFactor();
+    val *= encoder->GetDistancePerPulse();
+    return val;
+  }
+
+  int32_t GetEncoderPeriodRaw(const Encoder* encoder, int32_t* status) const {
+    return HAL_GetDMASampleEncoderPeriodRaw(this, encoder->m_encoder, status);
+  }
+
+  int32_t GetCounter(const Counter* counter, int32_t* status) const {
+    return HAL_GetDMASampleCounter(this, counter->m_counter, status);
+  }
+
+  int32_t GetCounterPeriod(const Counter* counter, int32_t* status) const {
+    return HAL_GetDMASampleCounterPeriod(this, counter->m_counter, status);
+  }
+
+  bool GetDigitalSource(const DigitalSource* digitalSource,
+                        int32_t* status) const {
+    return HAL_GetDMASampleDigitalSource(
+        this, digitalSource->GetPortHandleForRouting(), status);
+  }
+
+  int32_t GetAnalogInputRaw(const AnalogInput* analogInput,
+                            int32_t* status) const {
+    return HAL_GetDMASampleAnalogInputRaw(this, analogInput->m_port, status);
+  }
+
+  double GetAnalogInputVoltage(const AnalogInput* analogInput,
+                               int32_t* status) {
+    return HAL_GetAnalogValueToVolts(
+        analogInput->m_port, GetAnalogInputRaw(analogInput, status), status);
+  }
+
+  int32_t GetAveragedAnalogInputRaw(const AnalogInput* analogInput,
+                                    int32_t* status) const {
+    return HAL_GetDMASampleAveragedAnalogInputRaw(this, analogInput->m_port,
+                                                  status);
+  }
+
+  double GetAveragedAnalogInputVoltage(const AnalogInput* analogInput,
+                                       int32_t* status) {
+    return HAL_GetAnalogValueToVolts(
+        analogInput->m_port, GetAveragedAnalogInputRaw(analogInput, status),
+        status);
+  }
+
+  void GetAnalogAccumulator(const AnalogInput* analogInput, int64_t* count,
+                            int64_t* value, int32_t* status) const {
+    return HAL_GetDMASampleAnalogAccumulator(this, analogInput->m_port, count,
+                                             value, status);
+  }
+
+  int32_t GetDutyCycleOutputRaw(const DutyCycle* dutyCycle,
+                                int32_t* status) const {
+    return HAL_GetDMASampleDutyCycleOutputRaw(this, dutyCycle->m_handle,
+                                              status);
+  }
+
+  double GetDutyCycleOutput(const DutyCycle* dutyCycle, int32_t* status) {
+    return GetDutyCycleOutputRaw(dutyCycle, status) /
+           static_cast<double>(dutyCycle->GetOutputScaleFactor());
+  }
+};
+
+static_assert(std::is_standard_layout_v<frc::DMASample>,
+              "frc::DMASample must have standard layout");
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/DMC60.h b/wpilibc/src/main/native/include/frc/DMC60.h
new file mode 100644
index 0000000..ecf01e1
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/DMC60.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Digilent DMC 60 Speed Controller.
+ *
+ * Note that the DMC 60 uses the following bounds for PWM values. These
+ * values should work reasonably well for most controllers, but if users
+ * experience issues such as asymmetric behavior around the deadband or
+ * inability to saturate the controller in either direction, calibration is
+ * recommended. The calibration procedure can be found in the DMC 60 User
+ * Manual available from Digilent.
+ *
+ * \li 2.004ms = full "forward"
+ * \li 1.520ms = the "high end" of the deadband range
+ * \li 1.500ms = center of the deadband range (off)
+ * \li 1.480ms = the "low end" of the deadband range
+ * \li 0.997ms = full "reverse"
+ */
+class DMC60 : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a Digilent DMC 60.
+   *
+   * @param channel The PWM channel that the DMC 60 is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit DMC60(int channel);
+
+  DMC60(DMC60&&) = default;
+  DMC60& operator=(DMC60&&) = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/DigitalGlitchFilter.h b/wpilibc/src/main/native/include/frc/DigitalGlitchFilter.h
new file mode 100644
index 0000000..0690e53
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/DigitalGlitchFilter.h
@@ -0,0 +1,135 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <array>
+
+#include <wpi/mutex.h>
+
+#include "frc/DigitalSource.h"
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class Encoder;
+class Counter;
+
+/**
+ * Class to enable glitch filtering on a set of digital inputs.
+ *
+ * This class will manage adding and removing digital inputs from a FPGA glitch
+ * filter. The filter lets the user configure the time that an input must remain
+ * high or low before it is classified as high or low.
+ */
+class DigitalGlitchFilter : public ErrorBase,
+                            public Sendable,
+                            public SendableHelper<DigitalGlitchFilter> {
+ public:
+  DigitalGlitchFilter();
+  ~DigitalGlitchFilter() override;
+
+  DigitalGlitchFilter(DigitalGlitchFilter&& rhs);
+  DigitalGlitchFilter& operator=(DigitalGlitchFilter&& rhs);
+
+  /**
+   * Assigns the DigitalSource to this glitch filter.
+   *
+   * @param input The DigitalSource to add.
+   */
+  void Add(DigitalSource* input);
+
+  /**
+   * Assigns the Encoder to this glitch filter.
+   *
+   * @param input The Encoder to add.
+   */
+  void Add(Encoder* input);
+
+  /**
+   * Assigns the Counter to this glitch filter.
+   *
+   * @param input The Counter to add.
+   */
+  void Add(Counter* input);
+
+  /**
+   * Removes a digital input from this filter.
+   *
+   * Removes the DigitalSource from this glitch filter and re-assigns it to
+   * the default filter.
+   *
+   * @param input The DigitalSource to remove.
+   */
+  void Remove(DigitalSource* input);
+
+  /**
+   * Removes an encoder from this filter.
+   *
+   * Removes the Encoder from this glitch filter and re-assigns it to
+   * the default filter.
+   *
+   * @param input The Encoder to remove.
+   */
+  void Remove(Encoder* input);
+
+  /**
+   * Removes a counter from this filter.
+   *
+   * Removes the Counter from this glitch filter and re-assigns it to
+   * the default filter.
+   *
+   * @param input The Counter to remove.
+   */
+  void Remove(Counter* input);
+
+  /**
+   * Sets the number of cycles that the input must not change state for.
+   *
+   * @param fpgaCycles The number of FPGA cycles.
+   */
+  void SetPeriodCycles(int fpgaCycles);
+
+  /**
+   * Sets the number of nanoseconds that the input must not change state for.
+   *
+   * @param nanoseconds The number of nanoseconds.
+   */
+  void SetPeriodNanoSeconds(uint64_t nanoseconds);
+
+  /**
+   * Gets the number of cycles that the input must not change state for.
+   *
+   * @return The number of cycles.
+   */
+  int GetPeriodCycles();
+
+  /**
+   * Gets the number of nanoseconds that the input must not change state for.
+   *
+   * @return The number of nanoseconds.
+   */
+  uint64_t GetPeriodNanoSeconds();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  // Sets the filter for the input to be the requested index. A value of 0
+  // disables the filter, and the filter value must be between 1 and 3,
+  // inclusive.
+  void DoAdd(DigitalSource* input, int requested_index);
+
+  int m_channelIndex = -1;
+  static wpi::mutex m_mutex;
+  static std::array<bool, 3> m_filterAllocated;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/DigitalInput.h b/wpilibc/src/main/native/include/frc/DigitalInput.h
new file mode 100644
index 0000000..33aa716
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/DigitalInput.h
@@ -0,0 +1,90 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/DigitalSource.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class DigitalGlitchFilter;
+class SendableBuilder;
+
+/**
+ * Class to read a digital input.
+ *
+ * This class will read digital inputs and return the current value on the
+ * channel. Other devices such as encoders, gear tooth sensors, etc. that are
+ * implemented elsewhere will automatically allocate digital inputs and outputs
+ * as required. This class is only for devices like switches etc. that aren't
+ * implemented anywhere else.
+ */
+class DigitalInput : public DigitalSource,
+                     public Sendable,
+                     public SendableHelper<DigitalInput> {
+ public:
+  /**
+   * Create an instance of a Digital Input class.
+   *
+   * Creates a digital input given a channel.
+   *
+   * @param channel The DIO channel 0-9 are on-board, 10-25 are on the MXP port
+   */
+  explicit DigitalInput(int channel);
+
+  ~DigitalInput() override;
+
+  DigitalInput(DigitalInput&&) = default;
+  DigitalInput& operator=(DigitalInput&&) = default;
+
+  /**
+   * Get the value from a digital input channel.
+   *
+   * Retrieve the value of a single digital input channel from the FPGA.
+   */
+  bool Get() const;
+
+  // Digital Source Interface
+  /**
+   * @return The HAL Handle to the specified source.
+   */
+  HAL_Handle GetPortHandleForRouting() const override;
+
+  /**
+   * @return The type of analog trigger output to be used. 0 for Digitals
+   */
+  AnalogTriggerType GetAnalogTriggerTypeForRouting() const override;
+
+  /**
+   * Is source an AnalogTrigger
+   */
+  bool IsAnalogTrigger() const override;
+
+  /**
+   * @return The GPIO channel number that this object represents.
+   */
+  int GetChannel() const override;
+
+  /**
+   * Indicates this input is used by a simulated device.
+   *
+   * @param device simulated device handle
+   */
+  void SetSimDevice(HAL_SimDeviceHandle device);
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  int m_channel;
+  hal::Handle<HAL_DigitalHandle> m_handle;
+
+  friend class DigitalGlitchFilter;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/DigitalOutput.h b/wpilibc/src/main/native/include/frc/DigitalOutput.h
new file mode 100644
index 0000000..1d1d152
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/DigitalOutput.h
@@ -0,0 +1,159 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/DigitalSource.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+
+/**
+ * Class to write to digital outputs.
+ *
+ * Write values to the digital output channels. Other devices implemented
+ * elsewhere will allocate channels automatically so for those devices it
+ * shouldn't be done here.
+ */
+class DigitalOutput : public DigitalSource,
+                      public Sendable,
+                      public SendableHelper<DigitalOutput> {
+ public:
+  /**
+   * Create an instance of a digital output.
+   *
+   * Create a digital output given a channel.
+   *
+   * @param channel The digital channel 0-9 are on-board, 10-25 are on the MXP
+   *                port
+   */
+  explicit DigitalOutput(int channel);
+
+  ~DigitalOutput() override;
+
+  DigitalOutput(DigitalOutput&&) = default;
+  DigitalOutput& operator=(DigitalOutput&&) = default;
+
+  /**
+   * Set the value of a digital output.
+   *
+   * Set the value of a digital output to either one (true) or zero (false).
+   *
+   * @param value 1 (true) for high, 0 (false) for disabled
+   */
+  void Set(bool value);
+
+  /**
+   * Gets the value being output from the Digital Output.
+   *
+   * @return the state of the digital output.
+   */
+  bool Get() const;
+
+  // Digital Source Interface
+  /**
+   * @return The HAL Handle to the specified source.
+   */
+  HAL_Handle GetPortHandleForRouting() const override;
+
+  /**
+   * @return The type of analog trigger output to be used. 0 for Digitals
+   */
+  AnalogTriggerType GetAnalogTriggerTypeForRouting() const override;
+
+  /**
+   * Is source an AnalogTrigger
+   */
+  bool IsAnalogTrigger() const override;
+
+  /**
+   * @return The GPIO channel number that this object represents.
+   */
+  int GetChannel() const override;
+
+  /**
+   * Output a single pulse on the digital output line.
+   *
+   * Send a single pulse on the digital output line where the pulse duration is
+   * specified in seconds. Maximum pulse length is 0.0016 seconds.
+   *
+   * @param length The pulse length in seconds
+   */
+  void Pulse(double length);
+
+  /**
+   * Determine if the pulse is still going.
+   *
+   * Determine if a previously started pulse is still going.
+   */
+  bool IsPulsing() const;
+
+  /**
+   * Change the PWM frequency of the PWM output on a Digital Output line.
+   *
+   * The valid range is from 0.6 Hz to 19 kHz.  The frequency resolution is
+   * logarithmic.
+   *
+   * There is only one PWM frequency for all digital channels.
+   *
+   * @param rate The frequency to output all digital output PWM signals.
+   */
+  void SetPWMRate(double rate);
+
+  /**
+   * Enable a PWM Output on this line.
+   *
+   * Allocate one of the 6 DO PWM generator resources from this module.
+   *
+   * Supply the initial duty-cycle to output so as to avoid a glitch when first
+   * starting.
+   *
+   * The resolution of the duty cycle is 8-bit for low frequencies (1kHz or
+   * less) but is reduced the higher the frequency of the PWM signal is.
+   *
+   * @param initialDutyCycle The duty-cycle to start generating. [0..1]
+   */
+  void EnablePWM(double initialDutyCycle);
+
+  /**
+   * Change this line from a PWM output back to a static Digital Output line.
+   *
+   * Free up one of the 6 DO PWM generator resources that were in use.
+   */
+  void DisablePWM();
+
+  /**
+   * Change the duty-cycle that is being generated on the line.
+   *
+   * The resolution of the duty cycle is 8-bit for low frequencies (1kHz or
+   * less) but is reduced the higher the frequency of the PWM signal is.
+   *
+   * @param dutyCycle The duty-cycle to change to. [0..1]
+   */
+  void UpdateDutyCycle(double dutyCycle);
+
+  /**
+   * Indicates this output is used by a simulated device.
+   *
+   * @param device simulated device handle
+   */
+  void SetSimDevice(HAL_SimDeviceHandle device);
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  int m_channel;
+  hal::Handle<HAL_DigitalHandle> m_handle;
+  hal::Handle<HAL_DigitalPWMHandle> m_pwmGenerator;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/DigitalSource.h b/wpilibc/src/main/native/include/frc/DigitalSource.h
new file mode 100644
index 0000000..5d77daa
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/DigitalSource.h
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/InterruptableSensorBase.h"
+
+namespace frc {
+
+/**
+ * DigitalSource Interface.
+ *
+ * The DigitalSource represents all the possible inputs for a counter or a
+ * quadrature encoder. The source may be either a digital input or an analog
+ * input. If the caller just provides a channel, then a digital input will be
+ * constructed and freed when finished for the source. The source can either be
+ * a digital input or analog trigger but not both.
+ */
+class DigitalSource : public InterruptableSensorBase {
+ public:
+  DigitalSource() = default;
+  DigitalSource(DigitalSource&&) = default;
+  DigitalSource& operator=(DigitalSource&&) = default;
+
+  virtual HAL_Handle GetPortHandleForRouting() const = 0;
+  virtual AnalogTriggerType GetAnalogTriggerTypeForRouting() const = 0;
+  virtual bool IsAnalogTrigger() const = 0;
+  virtual int GetChannel() const = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/DoubleSolenoid.h b/wpilibc/src/main/native/include/frc/DoubleSolenoid.h
new file mode 100644
index 0000000..6722976
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/DoubleSolenoid.h
@@ -0,0 +1,104 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/SolenoidBase.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+
+/**
+ * DoubleSolenoid class for running 2 channels of high voltage Digital Output
+ * (PCM).
+ *
+ * The DoubleSolenoid class is typically used for pneumatics solenoids that
+ * have two positions controlled by two separate channels.
+ */
+class DoubleSolenoid : public SolenoidBase,
+                       public Sendable,
+                       public SendableHelper<DoubleSolenoid> {
+ public:
+  enum Value { kOff, kForward, kReverse };
+
+  /**
+   * Constructor.
+   *
+   * Uses the default PCM ID of 0.
+   *
+   * @param forwardChannel The forward channel number on the PCM (0..7).
+   * @param reverseChannel The reverse channel number on the PCM (0..7).
+   */
+  explicit DoubleSolenoid(int forwardChannel, int reverseChannel);
+
+  /**
+   * Constructor.
+   *
+   * @param moduleNumber   The CAN ID of the PCM.
+   * @param forwardChannel The forward channel on the PCM to control (0..7).
+   * @param reverseChannel The reverse channel on the PCM to control (0..7).
+   */
+  DoubleSolenoid(int moduleNumber, int forwardChannel, int reverseChannel);
+
+  ~DoubleSolenoid() override;
+
+  DoubleSolenoid(DoubleSolenoid&&) = default;
+  DoubleSolenoid& operator=(DoubleSolenoid&&) = default;
+
+  /**
+   * Set the value of a solenoid.
+   *
+   * @param value The value to set (Off, Forward or Reverse)
+   */
+  virtual void Set(Value value);
+
+  /**
+   * Read the current value of the solenoid.
+   *
+   * @return The current value of the solenoid.
+   */
+  virtual Value Get() const;
+
+  /**
+   * Check if the forward solenoid is blacklisted.
+   *
+   * If a solenoid is shorted, it is added to the blacklist and disabled until
+   * power cycle, or until faults are cleared.
+   *
+   * @see ClearAllPCMStickyFaults()
+   * @return If solenoid is disabled due to short.
+   */
+  bool IsFwdSolenoidBlackListed() const;
+
+  /**
+   * Check if the reverse solenoid is blacklisted.
+   *
+   * If a solenoid is shorted, it is added to the blacklist and disabled until
+   * power cycle, or until faults are cleared.
+   *
+   * @see ClearAllPCMStickyFaults()
+   * @return If solenoid is disabled due to short.
+   */
+  bool IsRevSolenoidBlackListed() const;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  int m_forwardChannel;  // The forward channel on the module to control.
+  int m_reverseChannel;  // The reverse channel on the module to control.
+  int m_forwardMask;     // The mask for the forward channel.
+  int m_reverseMask;     // The mask for the reverse channel.
+  hal::Handle<HAL_SolenoidHandle> m_forwardHandle;
+  hal::Handle<HAL_SolenoidHandle> m_reverseHandle;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/DriverStation.h b/wpilibc/src/main/native/include/frc/DriverStation.h
new file mode 100644
index 0000000..4508701
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/DriverStation.h
@@ -0,0 +1,462 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <array>
+#include <atomic>
+#include <memory>
+#include <string>
+#include <thread>
+
+#include <hal/DriverStationTypes.h>
+#include <wpi/Twine.h>
+#include <wpi/condition_variable.h>
+#include <wpi/deprecated.h>
+#include <wpi/mutex.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/RobotState.h"
+
+namespace frc {
+
+class MatchDataSender;
+
+/**
+ * Provide access to the network communication data to / from the Driver
+ * Station.
+ */
+class DriverStation : public ErrorBase {
+ public:
+  enum Alliance { kRed, kBlue, kInvalid };
+  enum MatchType { kNone, kPractice, kQualification, kElimination };
+
+  ~DriverStation() override;
+
+  DriverStation(const DriverStation&) = delete;
+  DriverStation& operator=(const DriverStation&) = delete;
+
+  /**
+   * Return a reference to the singleton DriverStation.
+   *
+   * @return Reference to the DS instance
+   */
+  static DriverStation& GetInstance();
+
+  /**
+   * Report an error to the DriverStation messages window.
+   *
+   * The error is also printed to the program console.
+   */
+  static void ReportError(const wpi::Twine& error);
+
+  /**
+   * Report a warning to the DriverStation messages window.
+   *
+   * The warning is also printed to the program console.
+   */
+  static void ReportWarning(const wpi::Twine& error);
+
+  /**
+   * Report an error to the DriverStation messages window.
+   *
+   * The error is also printed to the program console.
+   */
+  static void ReportError(bool isError, int code, const wpi::Twine& error,
+                          const wpi::Twine& location, const wpi::Twine& stack);
+
+  static constexpr int kJoystickPorts = 6;
+
+  /**
+   * The state of one joystick button. Button indexes begin at 1.
+   *
+   * @param stick  The joystick to read.
+   * @param button The button index, beginning at 1.
+   * @return The state of the joystick button.
+   */
+  bool GetStickButton(int stick, int button);
+
+  /**
+   * Whether one joystick button was pressed since the last check. Button
+   * indexes begin at 1.
+   *
+   * @param stick  The joystick to read.
+   * @param button The button index, beginning at 1.
+   * @return Whether the joystick button was pressed since the last check.
+   */
+  bool GetStickButtonPressed(int stick, int button);
+
+  /**
+   * Whether one joystick button was released since the last check. Button
+   * indexes begin at 1.
+   *
+   * @param stick  The joystick to read.
+   * @param button The button index, beginning at 1.
+   * @return Whether the joystick button was released since the last check.
+   */
+  bool GetStickButtonReleased(int stick, int button);
+
+  /**
+   * Get the value of the axis on a joystick.
+   *
+   * This depends on the mapping of the joystick connected to the specified
+   * port.
+   *
+   * @param stick The joystick to read.
+   * @param axis  The analog axis value to read from the joystick.
+   * @return The value of the axis on the joystick.
+   */
+  double GetStickAxis(int stick, int axis);
+
+  /**
+   * Get the state of a POV on the joystick.
+   *
+   * @return the angle of the POV in degrees, or -1 if the POV is not pressed.
+   */
+  int GetStickPOV(int stick, int pov);
+
+  /**
+   * The state of the buttons on the joystick.
+   *
+   * @param stick The joystick to read.
+   * @return The state of the buttons on the joystick.
+   */
+  int GetStickButtons(int stick) const;
+
+  /**
+   * Returns the number of axes on a given joystick port.
+   *
+   * @param stick The joystick port number
+   * @return The number of axes on the indicated joystick
+   */
+  int GetStickAxisCount(int stick) const;
+
+  /**
+   * Returns the number of POVs on a given joystick port.
+   *
+   * @param stick The joystick port number
+   * @return The number of POVs on the indicated joystick
+   */
+  int GetStickPOVCount(int stick) const;
+
+  /**
+   * Returns the number of buttons on a given joystick port.
+   *
+   * @param stick The joystick port number
+   * @return The number of buttons on the indicated joystick
+   */
+  int GetStickButtonCount(int stick) const;
+
+  /**
+   * Returns a boolean indicating if the controller is an xbox controller.
+   *
+   * @param stick The joystick port number
+   * @return A boolean that is true if the controller is an xbox controller.
+   */
+  bool GetJoystickIsXbox(int stick) const;
+
+  /**
+   * Returns the type of joystick at a given port.
+   *
+   * @param stick The joystick port number
+   * @return The HID type of joystick at the given port
+   */
+  int GetJoystickType(int stick) const;
+
+  /**
+   * Returns the name of the joystick at the given port.
+   *
+   * @param stick The joystick port number
+   * @return The name of the joystick at the given port
+   */
+  std::string GetJoystickName(int stick) const;
+
+  /**
+   * Returns the types of Axes on a given joystick port.
+   *
+   * @param stick The joystick port number and the target axis
+   * @return What type of axis the axis is reporting to be
+   */
+  int GetJoystickAxisType(int stick, int axis) const;
+
+  /**
+   * Check if the DS has enabled the robot.
+   *
+   * @return True if the robot is enabled and the DS is connected
+   */
+  bool IsEnabled() const;
+
+  /**
+   * Check if the robot is disabled.
+   *
+   * @return True if the robot is explicitly disabled or the DS is not connected
+   */
+  bool IsDisabled() const;
+
+  /**
+   * Check if the robot is e-stopped.
+   *
+   * @return True if the robot is e-stopped
+   */
+  bool IsEStopped() const;
+
+  /**
+   * Check if the DS is commanding autonomous mode.
+   *
+   * @return True if the robot is being commanded to be in autonomous mode
+   */
+  bool IsAutonomous() const;
+
+  /**
+   * Check if the DS is commanding teleop mode.
+   *
+   * @return True if the robot is being commanded to be in teleop mode
+   */
+  bool IsOperatorControl() const;
+
+  /**
+   * Check if the DS is commanding test mode.
+   *
+   * @return True if the robot is being commanded to be in test mode
+   */
+  bool IsTest() const;
+
+  /**
+   * Check if the DS is attached.
+   *
+   * @return True if the DS is connected to the robot
+   */
+  bool IsDSAttached() const;
+
+  /**
+   * Has a new control packet from the driver station arrived since the last
+   * time this function was called?
+   *
+   * Warning: If you call this function from more than one place at the same
+   * time, you will not get the intended behavior.
+   *
+   * @return True if the control data has been updated since the last call.
+   */
+  bool IsNewControlData() const;
+
+  /**
+   * Is the driver station attached to a Field Management System?
+   *
+   * @return True if the robot is competing on a field being controlled by a
+   *         Field Management System
+   */
+  bool IsFMSAttached() const;
+
+  /**
+   * Returns the game specific message provided by the FMS.
+   *
+   * @return A string containing the game specific message.
+   */
+  std::string GetGameSpecificMessage() const;
+
+  /**
+   * Returns the name of the competition event provided by the FMS.
+   *
+   * @return A string containing the event name
+   */
+  std::string GetEventName() const;
+
+  /**
+   * Returns the type of match being played provided by the FMS.
+   *
+   * @return The match type enum (kNone, kPractice, kQualification,
+   *         kElimination)
+   */
+  MatchType GetMatchType() const;
+
+  /**
+   * Returns the match number provided by the FMS.
+   *
+   * @return The number of the match
+   */
+  int GetMatchNumber() const;
+
+  /**
+   * Returns the number of times the current match has been replayed from the
+   * FMS.
+   *
+   * @return The number of replays
+   */
+  int GetReplayNumber() const;
+
+  /**
+   * Return the alliance that the driver station says it is on.
+   *
+   * This could return kRed or kBlue.
+   *
+   * @return The Alliance enum (kRed, kBlue or kInvalid)
+   */
+  Alliance GetAlliance() const;
+
+  /**
+   * Return the driver station location on the field.
+   *
+   * This could return 1, 2, or 3.
+   *
+   * @return The location of the driver station (1-3, 0 for invalid)
+   */
+  int GetLocation() const;
+
+  /**
+   * Wait until a new packet comes from the driver station.
+   *
+   * This blocks on a semaphore, so the waiting is efficient.
+   *
+   * This is a good way to delay processing until there is new driver station
+   * data to act on.
+   */
+  void WaitForData();
+
+  /**
+   * Wait until a new packet comes from the driver station, or wait for a
+   * timeout.
+   *
+   * If the timeout is less then or equal to 0, wait indefinitely.
+   *
+   * Timeout is in milliseconds
+   *
+   * This blocks on a semaphore, so the waiting is efficient.
+   *
+   * This is a good way to delay processing until there is new driver station
+   * data to act on.
+   *
+   * @param timeout Timeout time in seconds
+   *
+   * @return true if new data, otherwise false
+   */
+  bool WaitForData(double timeout);
+
+  /**
+   * Return the approximate match time.
+   *
+   * The FMS does not send an official match time to the robots, but does send
+   * an approximate match time. The value will count down the time remaining in
+   * the current period (auto or teleop).
+   *
+   * Warning: This is not an official time (so it cannot be used to dispute ref
+   * calls or guarantee that a function will trigger before the match ends).
+   *
+   * The Practice Match function of the DS approximates the behaviour seen on
+   * the field.
+   *
+   * @return Time remaining in current match period (auto or teleop)
+   */
+  double GetMatchTime() const;
+
+  /**
+   * Read the battery voltage.
+   *
+   * @return The battery voltage in Volts.
+   */
+  double GetBatteryVoltage() const;
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only.
+   *
+   * @param entering If true, starting disabled code; if false, leaving disabled
+   *                 code.
+   */
+  void InDisabled(bool entering) { m_userInDisabled = entering; }
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only.
+   *
+   * @param entering If true, starting autonomous code; if false, leaving
+   *                 autonomous code.
+   */
+  void InAutonomous(bool entering) { m_userInAutonomous = entering; }
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only.
+   *
+   * @param entering If true, starting teleop code; if false, leaving teleop
+   *                 code.
+   */
+  void InOperatorControl(bool entering) { m_userInTeleop = entering; }
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only.
+   *
+   * @param entering If true, starting test code; if false, leaving test code.
+   */
+  void InTest(bool entering) { m_userInTest = entering; }
+
+  /**
+   * Forces WaitForData() to return immediately.
+   */
+  void WakeupWaitForData();
+
+ protected:
+  /**
+   * Copy data from the DS task for the user.
+   *
+   * If no new data exists, it will just be returned, otherwise
+   * the data will be copied from the DS polling loop.
+   */
+  void GetData();
+
+ private:
+  /**
+   * DriverStation constructor.
+   *
+   * This is only called once the first time GetInstance() is called
+   */
+  DriverStation();
+
+  /**
+   * Reports errors related to unplugged joysticks.
+   *
+   * Throttles the errors so that they don't overwhelm the DS.
+   */
+  void ReportJoystickUnpluggedError(const wpi::Twine& message);
+
+  /**
+   * Reports errors related to unplugged joysticks.
+   *
+   * Throttles the errors so that they don't overwhelm the DS.
+   */
+  void ReportJoystickUnpluggedWarning(const wpi::Twine& message);
+
+  void Run();
+
+  void SendMatchData();
+
+  std::unique_ptr<MatchDataSender> m_matchDataSender;
+
+  // Joystick button rising/falling edge flags
+  wpi::mutex m_buttonEdgeMutex;
+  std::array<HAL_JoystickButtons, kJoystickPorts> m_previousButtonStates;
+  std::array<uint32_t, kJoystickPorts> m_joystickButtonsPressed;
+  std::array<uint32_t, kJoystickPorts> m_joystickButtonsReleased;
+
+  // Internal Driver Station thread
+  std::thread m_dsThread;
+  std::atomic<bool> m_isRunning{false};
+
+  wpi::mutex m_waitForDataMutex;
+  wpi::condition_variable m_waitForDataCond;
+  int m_waitForDataCounter;
+
+  // Robot state status variables
+  bool m_userInDisabled = false;
+  bool m_userInAutonomous = false;
+  bool m_userInTeleop = false;
+  bool m_userInTest = false;
+
+  double m_nextMessageTime = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/DutyCycle.h b/wpilibc/src/main/native/include/frc/DutyCycle.h
new file mode 100644
index 0000000..f0fc2d8
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/DutyCycle.h
@@ -0,0 +1,135 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <hal/Types.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+class DigitalSource;
+class AnalogTrigger;
+class DMA;
+class DMASample;
+
+/**
+ * Class to read a duty cycle PWM input.
+ *
+ * <p>PWM input signals are specified with a frequency and a ratio of high to
+ * low in that frequency. There are 8 of these in the roboRIO, and they can be
+ * attached to any DigitalSource.
+ *
+ * <p>These can be combined as the input of an AnalogTrigger to a Counter in
+ * order to implement rollover checking.
+ *
+ */
+class DutyCycle : public ErrorBase,
+                  public Sendable,
+                  public SendableHelper<DutyCycle> {
+  friend class AnalogTrigger;
+  friend class DMA;
+  friend class DMASample;
+
+ public:
+  /**
+   * Constructs a DutyCycle input from a DigitalSource input.
+   *
+   * <p> This class does not own the inputted source.
+   *
+   * @param source The DigitalSource to use.
+   */
+  explicit DutyCycle(DigitalSource& source);
+  /**
+   * Constructs a DutyCycle input from a DigitalSource input.
+   *
+   * <p> This class does not own the inputted source.
+   *
+   * @param source The DigitalSource to use.
+   */
+  explicit DutyCycle(DigitalSource* source);
+  /**
+   * Constructs a DutyCycle input from a DigitalSource input.
+   *
+   * <p> This class does not own the inputted source.
+   *
+   * @param source The DigitalSource to use.
+   */
+  explicit DutyCycle(std::shared_ptr<DigitalSource> source);
+
+  /**
+   * Close the DutyCycle and free all resources.
+   */
+  ~DutyCycle() override;
+
+  DutyCycle(DutyCycle&&) = default;
+  DutyCycle& operator=(DutyCycle&&) = default;
+
+  /**
+   * Get the frequency of the duty cycle signal.
+   *
+   * @return frequency in Hertz
+   */
+  int GetFrequency() const;
+
+  /**
+   * Get the output ratio of the duty cycle signal.
+   *
+   * <p> 0 means always low, 1 means always high.
+   *
+   * @return output ratio between 0 and 1
+   */
+  double GetOutput() const;
+
+  /**
+   * Get the raw output ratio of the duty cycle signal.
+   *
+   * <p> 0 means always low, an output equal to
+   * GetOutputScaleFactor() means always high.
+   *
+   * @return output ratio in raw units
+   */
+  unsigned int GetOutputRaw() const;
+
+  /**
+   * Get the scale factor of the output.
+   *
+   * <p> An output equal to this value is always high, and then linearly scales
+   * down to 0. Divide the result of getOutputRaw by this in order to get the
+   * percentage between 0 and 1.
+   *
+   * @return the output scale factor
+   */
+  unsigned int GetOutputScaleFactor() const;
+
+  /**
+   * Get the FPGA index for the DutyCycle.
+   *
+   * @return the FPGA index
+   */
+  int GetFPGAIndex() const;
+
+  /**
+   * Get the channel of the source.
+   *
+   * @return the source channel
+   */
+  int GetSourceChannel() const;
+
+ protected:
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  void InitDutyCycle();
+  std::shared_ptr<DigitalSource> m_source;
+  hal::Handle<HAL_DutyCycleHandle> m_handle;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/DutyCycleEncoder.h b/wpilibc/src/main/native/include/frc/DutyCycleEncoder.h
new file mode 100644
index 0000000..92864a8
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/DutyCycleEncoder.h
@@ -0,0 +1,174 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <hal/SimDevice.h>
+#include <hal/Types.h>
+#include <units/units.h>
+
+#include "frc/AnalogTrigger.h"
+#include "frc/Counter.h"
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+class DutyCycle;
+class DigitalSource;
+
+/**
+ * Class for supporting duty cycle/PWM encoders, such as the US Digital MA3 with
+ * PWM Output, the CTRE Mag Encoder, the Rev Hex Encoder, and the AM Mag
+ * Encoder.
+ */
+class DutyCycleEncoder : public ErrorBase,
+                         public Sendable,
+                         public SendableHelper<DutyCycleEncoder> {
+ public:
+  /**
+   * Construct a new DutyCycleEncoder on a specific channel.
+   *
+   * @param channel the channel to attach to
+   */
+  explicit DutyCycleEncoder(int channel);
+
+  /**
+   * Construct a new DutyCycleEncoder attached to an existing DutyCycle object.
+   *
+   * @param dutyCycle the duty cycle to attach to
+   */
+  explicit DutyCycleEncoder(DutyCycle& dutyCycle);
+
+  /**
+   * Construct a new DutyCycleEncoder attached to an existing DutyCycle object.
+   *
+   * @param dutyCycle the duty cycle to attach to
+   */
+  explicit DutyCycleEncoder(DutyCycle* dutyCycle);
+
+  /**
+   * Construct a new DutyCycleEncoder attached to an existing DutyCycle object.
+   *
+   * @param dutyCycle the duty cycle to attach to
+   */
+  explicit DutyCycleEncoder(std::shared_ptr<DutyCycle> dutyCycle);
+
+  /**
+   * Construct a new DutyCycleEncoder attached to a DigitalSource object.
+   *
+   * @param source the digital source to attach to
+   */
+  explicit DutyCycleEncoder(DigitalSource& digitalSource);
+
+  /**
+   * Construct a new DutyCycleEncoder attached to a DigitalSource object.
+   *
+   * @param source the digital source to attach to
+   */
+  explicit DutyCycleEncoder(DigitalSource* digitalSource);
+
+  /**
+   * Construct a new DutyCycleEncoder attached to a DigitalSource object.
+   *
+   * @param source the digital source to attach to
+   */
+  explicit DutyCycleEncoder(std::shared_ptr<DigitalSource> digitalSource);
+
+  ~DutyCycleEncoder() override = default;
+
+  DutyCycleEncoder(DutyCycleEncoder&&) = default;
+  DutyCycleEncoder& operator=(DutyCycleEncoder&&) = default;
+
+  /**
+   * Get the frequency in Hz of the duty cycle signal from the encoder.
+   *
+   * @return duty cycle frequency in Hz
+   */
+  int GetFrequency() const;
+
+  /**
+   * Get if the sensor is connected
+   *
+   * This uses the duty cycle frequency to determine if the sensor is connected.
+   * By default, a value of 100 Hz is used as the threshold, and this value can
+   * be changed with SetConnectedFrequencyThreshold.
+   *
+   * @return true if the sensor is connected
+   */
+  bool IsConnected() const;
+
+  /**
+   * Change the frequency threshold for detecting connection used by
+   * IsConnected.
+   *
+   * @param frequency the minimum frequency in Hz.
+   */
+  void SetConnectedFrequencyThreshold(int frequency);
+
+  /**
+   * Reset the Encoder distance to zero.
+   */
+  void Reset();
+
+  /**
+   * Get the encoder value since the last reset.
+   *
+   * This is reported in rotations since the last reset.
+   *
+   * @return the encoder value in rotations
+   */
+  units::turn_t Get() const;
+
+  /**
+   * Set the distance per rotation of the encoder. This sets the multiplier used
+   * to determine the distance driven based on the rotation value from the
+   * encoder. Set this value based on the how far the mechanism travels in 1
+   * rotation of the encoder, and factor in gearing reductions following the
+   * encoder shaft. This distance can be in any units you like, linear or
+   * angular.
+   *
+   * @param distancePerRotation the distance per rotation of the encoder
+   */
+  void SetDistancePerRotation(double distancePerRotation);
+
+  /**
+   * Get the distance per rotation for this encoder.
+   *
+   * @return The scale factor that will be used to convert rotation to useful
+   * units.
+   */
+  double GetDistancePerRotation() const;
+
+  /**
+   * Get the distance the sensor has driven since the last reset as scaled by
+   * the value from SetDistancePerRotation.
+   *
+   * @return The distance driven since the last reset
+   */
+  double GetDistance() const;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  void Init();
+
+  std::shared_ptr<DutyCycle> m_dutyCycle;
+  AnalogTrigger m_analogTrigger;
+  Counter m_counter;
+  int m_frequencyThreshold = 100;
+  double m_positionOffset = 0;
+  double m_distancePerRotation = 1.0;
+  mutable units::turn_t m_lastPosition{0.0};
+
+  hal::SimDevice m_simDevice;
+  hal::SimDouble m_simPosition;
+  hal::SimBoolean m_simIsConnected;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Encoder.h b/wpilibc/src/main/native/include/frc/Encoder.h
new file mode 100644
index 0000000..60552f6
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Encoder.h
@@ -0,0 +1,385 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <hal/Types.h>
+
+#include "frc/Counter.h"
+#include "frc/CounterBase.h"
+#include "frc/ErrorBase.h"
+#include "frc/PIDSource.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class DigitalSource;
+class DigitalGlitchFilter;
+class SendableBuilder;
+class DMA;
+class DMASample;
+
+/**
+ * Class to read quad encoders.
+ *
+ * Quadrature encoders are devices that count shaft rotation and can sense
+ * direction. The output of the QuadEncoder class is an integer that can count
+ * either up or down, and can go negative for reverse direction counting. When
+ * creating QuadEncoders, a direction is supplied that changes the sense of the
+ * output to make code more readable if the encoder is mounted such that forward
+ * movement generates negative values. Quadrature encoders have two digital
+ * outputs, an A Channel and a B Channel that are out of phase with each other
+ * to allow the FPGA to do direction sensing.
+ *
+ * All encoders will immediately start counting - Reset() them if you need them
+ * to be zeroed before use.
+ */
+class Encoder : public ErrorBase,
+                public CounterBase,
+                public PIDSource,
+                public Sendable,
+                public SendableHelper<Encoder> {
+  friend class DMA;
+  friend class DMASample;
+
+ public:
+  enum IndexingType {
+    kResetWhileHigh,
+    kResetWhileLow,
+    kResetOnFallingEdge,
+    kResetOnRisingEdge
+  };
+
+  /**
+   * Encoder constructor.
+   *
+   * Construct a Encoder given a and b channels.
+   *
+   * The counter will start counting immediately.
+   *
+   * @param aChannel         The a channel DIO channel. 0-9 are on-board, 10-25
+   *                         are on the MXP port
+   * @param bChannel         The b channel DIO channel. 0-9 are on-board, 10-25
+   *                         are on the MXP port
+   * @param reverseDirection represents the orientation of the encoder and
+   *                         inverts the output values if necessary so forward
+   *                         represents positive values.
+   * @param encodingType     either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+   *                         decoding. If 4X is selected, then an encoder FPGA
+   *                         object is used and the returned counts will be 4x
+   *                         the encoder spec'd value since all rising and
+   *                         falling edges are counted. If 1X or 2X are selected
+   *                         then a counter object will be used and the returned
+   *                         value will either exactly match the spec'd count or
+   *                         be double (2x) the spec'd count.
+   */
+  Encoder(int aChannel, int bChannel, bool reverseDirection = false,
+          EncodingType encodingType = k4X);
+
+  /**
+   * Encoder constructor.
+   *
+   * Construct a Encoder given a and b channels as digital inputs. This is used
+   * in the case where the digital inputs are shared. The Encoder class will not
+   * allocate the digital inputs and assume that they already are counted.
+   *
+   * The counter will start counting immediately.
+   *
+   * @param aSource          The source that should be used for the a channel.
+   * @param bSource          the source that should be used for the b channel.
+   * @param reverseDirection represents the orientation of the encoder and
+   *                         inverts the output values if necessary so forward
+   *                         represents positive values.
+   * @param encodingType     either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+   *                         decoding. If 4X is selected, then an encoder FPGA
+   *                         object is used and the returned counts will be 4x
+   *                         the encoder spec'd value since all rising and
+   *                         falling edges are counted. If 1X or 2X are selected
+   *                         then a counter object will be used and the returned
+   *                         value will either exactly match the spec'd count or
+   *                         be double (2x) the spec'd count.
+   */
+  Encoder(DigitalSource* aSource, DigitalSource* bSource,
+          bool reverseDirection = false, EncodingType encodingType = k4X);
+
+  /**
+   * Encoder constructor.
+   *
+   * Construct a Encoder given a and b channels as digital inputs. This is used
+   * in the case where the digital inputs are shared. The Encoder class will not
+   * allocate the digital inputs and assume that they already are counted.
+   *
+   * The counter will start counting immediately.
+   *
+   * @param aSource          The source that should be used for the a channel.
+   * @param bSource          the source that should be used for the b channel.
+   * @param reverseDirection represents the orientation of the encoder and
+   *                         inverts the output values if necessary so forward
+   *                         represents positive values.
+   * @param encodingType     either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+   *                         decoding. If 4X is selected, then an encoder FPGA
+   *                         object is used and the returned counts will be 4x
+   *                         the encoder spec'd value since all rising and
+   *                         falling edges are counted. If 1X or 2X are selected
+   *                         then a counter object will be used and the returned
+   *                         value will either exactly match the spec'd count or
+   *                         be double (2x) the spec'd count.
+   */
+  Encoder(DigitalSource& aSource, DigitalSource& bSource,
+          bool reverseDirection = false, EncodingType encodingType = k4X);
+
+  Encoder(std::shared_ptr<DigitalSource> aSource,
+          std::shared_ptr<DigitalSource> bSource, bool reverseDirection = false,
+          EncodingType encodingType = k4X);
+
+  ~Encoder() override;
+
+  Encoder(Encoder&&) = default;
+  Encoder& operator=(Encoder&&) = default;
+
+  // CounterBase interface
+  /**
+   * Gets the current count.
+   *
+   * Returns the current count on the Encoder. This method compensates for the
+   * decoding type.
+   *
+   * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x scale
+   *         factor.
+   */
+  int Get() const override;
+
+  /**
+   * Reset the Encoder distance to zero.
+   *
+   * Resets the current count to zero on the encoder.
+   */
+  void Reset() override;
+
+  /**
+   * Returns the period of the most recent pulse.
+   *
+   * Returns the period of the most recent Encoder pulse in seconds. This method
+   * compensates for the decoding type.
+   *
+   * Warning: This returns unscaled periods. Use GetRate() for rates that are
+   * scaled using the value from SetDistancePerPulse().
+   *
+   * @return Period in seconds of the most recent pulse.
+   */
+  double GetPeriod() const override;
+
+  /**
+   * Sets the maximum period for stopped detection.
+   *
+   * Sets the value that represents the maximum period of the Encoder before it
+   * will assume that the attached device is stopped. This timeout allows users
+   * to determine if the wheels or other shaft has stopped rotating.
+   * This method compensates for the decoding type.
+   *
+   * @deprecated Use SetMinRate() in favor of this method.  This takes unscaled
+   *             periods and SetMinRate() scales using value from
+   *             SetDistancePerPulse().
+   *
+   * @param maxPeriod The maximum time between rising and falling edges before
+   *                  the FPGA will report the device stopped. This is expressed
+   *                  in seconds.
+   */
+  void SetMaxPeriod(double maxPeriod) override;
+
+  /**
+   * Determine if the encoder is stopped.
+   *
+   * Using the MaxPeriod value, a boolean is returned that is true if the
+   * encoder is considered stopped and false if it is still moving. A stopped
+   * encoder is one where the most recent pulse width exceeds the MaxPeriod.
+   *
+   * @return True if the encoder is considered stopped.
+   */
+  bool GetStopped() const override;
+
+  /**
+   * The last direction the encoder value changed.
+   *
+   * @return The last direction the encoder value changed.
+   */
+  bool GetDirection() const override;
+
+  /**
+   * Gets the raw value from the encoder.
+   *
+   * The raw value is the actual count unscaled by the 1x, 2x, or 4x scale
+   * factor.
+   *
+   * @return Current raw count from the encoder
+   */
+  int GetRaw() const;
+
+  /**
+   * The encoding scale factor 1x, 2x, or 4x, per the requested encodingType.
+   *
+   * Used to divide raw edge counts down to spec'd counts.
+   */
+  int GetEncodingScale() const;
+
+  /**
+   * Get the distance the robot has driven since the last reset.
+   *
+   * @return The distance driven since the last reset as scaled by the value
+   *         from SetDistancePerPulse().
+   */
+  double GetDistance() const;
+
+  /**
+   * Get the current rate of the encoder.
+   *
+   * Units are distance per second as scaled by the value from
+   * SetDistancePerPulse().
+   *
+   * @return The current rate of the encoder.
+   */
+  double GetRate() const;
+
+  /**
+   * Set the minimum rate of the device before the hardware reports it stopped.
+   *
+   * @param minRate The minimum rate.  The units are in distance per second as
+   *                scaled by the value from SetDistancePerPulse().
+   */
+  void SetMinRate(double minRate);
+
+  /**
+   * Set the distance per pulse for this encoder.
+   *
+   * This sets the multiplier used to determine the distance driven based on the
+   * count value from the encoder.
+   *
+   * Do not include the decoding type in this scale.  The library already
+   * compensates for the decoding type.
+   *
+   * Set this value based on the encoder's rated Pulses per Revolution and
+   * factor in gearing reductions following the encoder shaft.
+   *
+   * This distance can be in any units you like, linear or angular.
+   *
+   * @param distancePerPulse The scale factor that will be used to convert
+   *                         pulses to useful units.
+   */
+  void SetDistancePerPulse(double distancePerPulse);
+
+  /**
+   * Get the distance per pulse for this encoder.
+   *
+   * @return The scale factor that will be used to convert pulses to useful
+   *         units.
+   */
+  double GetDistancePerPulse() const;
+
+  /**
+   * Set the direction sensing for this encoder.
+   *
+   * This sets the direction sensing on the encoder so that it could count in
+   * the correct software direction regardless of the mounting.
+   *
+   * @param reverseDirection true if the encoder direction should be reversed
+   */
+  void SetReverseDirection(bool reverseDirection);
+
+  /**
+   * Set the Samples to Average which specifies the number of samples of the
+   * timer to average when calculating the period.
+   *
+   * Perform averaging to account for mechanical imperfections or as
+   * oversampling to increase resolution.
+   *
+   * @param samplesToAverage The number of samples to average from 1 to 127.
+   */
+  void SetSamplesToAverage(int samplesToAverage);
+
+  /**
+   * Get the Samples to Average which specifies the number of samples of the
+   * timer to average when calculating the period.
+   *
+   * Perform averaging to account for mechanical imperfections or as
+   * oversampling to increase resolution.
+   *
+   * @return The number of samples being averaged (from 1 to 127)
+   */
+  int GetSamplesToAverage() const;
+
+  double PIDGet() override;
+
+  /**
+   * Set the index source for the encoder.
+   *
+   * When this source is activated, the encoder count automatically resets.
+   *
+   * @param channel A DIO channel to set as the encoder index
+   * @param type    The state that will cause the encoder to reset
+   */
+  void SetIndexSource(int channel, IndexingType type = kResetOnRisingEdge);
+
+  /**
+   * Set the index source for the encoder.
+   *
+   * When this source is activated, the encoder count automatically resets.
+   *
+   * @param channel A digital source to set as the encoder index
+   * @param type    The state that will cause the encoder to reset
+   */
+  void SetIndexSource(const DigitalSource& source,
+                      IndexingType type = kResetOnRisingEdge);
+
+  /**
+   * Indicates this encoder is used by a simulated device.
+   *
+   * @param device simulated device handle
+   */
+  void SetSimDevice(HAL_SimDeviceHandle device);
+
+  int GetFPGAIndex() const;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  /**
+   * Common initialization code for Encoders.
+   *
+   * This code allocates resources for Encoders and is common to all
+   * constructors. The counter will start counting immediately.
+   *
+   * @param reverseDirection If true, counts down instead of up (this is all
+   *                         relative)
+   * @param encodingType     either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+   *                         decoding. If 4X is selected, then an encoder FPGA
+   *                         object is used and the returned counts will be 4x
+   *                         the encoder spec'd value since all rising and
+   *                         falling edges are counted. If 1X or 2X are selected
+   *                         then a counter object will be used and the returned
+   *                         value will either exactly match the spec'd count or
+   *                         be double (2x) the spec'd count.
+   */
+  void InitEncoder(bool reverseDirection, EncodingType encodingType);
+
+  /**
+   * The scale needed to convert a raw counter value into a number of encoder
+   * pulses.
+   */
+  double DecodingScaleFactor() const;
+
+  std::shared_ptr<DigitalSource> m_aSource;  // The A phase of the quad encoder
+  std::shared_ptr<DigitalSource> m_bSource;  // The B phase of the quad encoder
+  std::shared_ptr<DigitalSource> m_indexSource = nullptr;
+  hal::Handle<HAL_EncoderHandle> m_encoder;
+
+  friend class DigitalGlitchFilter;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Error.h b/wpilibc/src/main/native/include/frc/Error.h
new file mode 100644
index 0000000..8eafd10
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Error.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <string>
+
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+
+#ifdef _WIN32
+#pragma push_macro("GetMessage")
+#undef GetMessage
+#endif
+
+#include "frc/Base.h"
+
+namespace frc {
+
+class ErrorBase;
+
+/**
+ * Error object represents a library error.
+ */
+class Error {
+ public:
+  using Code = int;
+
+  Error() = default;
+  Error(Code code, const wpi::Twine& contextMessage, wpi::StringRef filename,
+        wpi::StringRef function, int lineNumber,
+        const ErrorBase* originatingObject);
+
+  bool operator<(const Error& rhs) const;
+
+  Code GetCode() const;
+  std::string GetMessage() const;
+  std::string GetFilename() const;
+  std::string GetFunction() const;
+  int GetLineNumber() const;
+  const ErrorBase* GetOriginatingObject() const;
+  double GetTimestamp() const;
+  void Clear();
+  void Set(Code code, const wpi::Twine& contextMessage, wpi::StringRef filename,
+           wpi::StringRef function, int lineNumber,
+           const ErrorBase* originatingObject);
+
+ private:
+  void Report();
+
+  Code m_code = 0;
+  std::string m_message;
+  std::string m_filename;
+  std::string m_function;
+  int m_lineNumber = 0;
+  const ErrorBase* m_originatingObject = nullptr;
+  double m_timestamp = 0.0;
+};
+
+}  // namespace frc
+
+#ifdef _WIN32
+#pragma pop_macro("GetMessage")
+#endif
diff --git a/wpilibc/src/main/native/include/frc/ErrorBase.h b/wpilibc/src/main/native/include/frc/ErrorBase.h
new file mode 100644
index 0000000..e9168aa
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/ErrorBase.h
@@ -0,0 +1,244 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <vector>
+
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/mutex.h>
+
+#include "frc/Base.h"
+#include "frc/Error.h"
+
+// Forward declared manually to avoid needing to pull in entire HAL header.
+extern "C" const char* HAL_GetErrorMessage(int32_t code);
+
+#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_setHALError(code)                                     \
+  do {                                                            \
+    if ((code) != 0)                                              \
+      this->SetError((code), HAL_GetErrorMessage(code), __FILE__, \
+                     __FUNCTION__, __LINE__);                     \
+  } while (0)
+
+#define wpi_setHALErrorWithRange(code, min, max, req)                        \
+  do {                                                                       \
+    if ((code) != 0)                                                         \
+      this->SetErrorRange((code), (min), (max), (req),                       \
+                          HAL_GetErrorMessage(code), __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_setGlobalHALError(code)                                       \
+  do {                                                                    \
+    if ((code) != 0)                                                      \
+      ::frc::ErrorBase::SetGlobalError((code), HAL_GetErrorMessage(code), \
+                                       __FILE__, __FUNCTION__, __LINE__); \
+  } while (0)
+
+#define wpi_setGlobalError(code) wpi_setGlobalErrorWithContext(code, "")
+#define wpi_setWPIErrorWithContext(error, context)                    \
+  this->SetWPIError(wpi_error_s_##error(), wpi_error_value_##error(), \
+                    (context), __FILE__, __FUNCTION__, __LINE__)
+#define wpi_setWPIError(error) (wpi_setWPIErrorWithContext(error, ""))
+#define wpi_setStaticWPIErrorWithContext(object, error, context)  \
+  object->SetWPIError(wpi_error_s_##error(), (context), __FILE__, \
+                      __FUNCTION__, __LINE__)
+#define wpi_setStaticWPIError(object, error) \
+  wpi_setStaticWPIErrorWithContext(object, error, "")
+#define wpi_setGlobalWPIErrorWithContext(error, context)                \
+  ::frc::ErrorBase::SetGlobalWPIError(wpi_error_s_##error(), (context), \
+                                      __FILE__, __FUNCTION__, __LINE__)
+#define wpi_setGlobalWPIError(error) wpi_setGlobalWPIErrorWithContext(error, "")
+
+namespace frc {
+
+/**
+ * Base class for most objects.
+ *
+ * ErrorBase is the base class for most objects since it holds the generated
+ * error for that object. In addition, there is a single instance of a global
+ * error object.
+ */
+class ErrorBase {
+  // TODO: Consider initializing instance variables and cleanup in destructor
+ public:
+  ErrorBase();
+  virtual ~ErrorBase() = default;
+
+  ErrorBase(const ErrorBase&) = default;
+  ErrorBase& operator=(const ErrorBase&) = default;
+  ErrorBase(ErrorBase&&) = default;
+  ErrorBase& operator=(ErrorBase&&) = default;
+
+  /**
+   * @brief Retrieve the current error.
+   *
+   * Get the current error information associated with this sensor.
+   */
+  virtual Error& GetError();
+
+  /**
+   * @brief Retrieve the current error.
+   *
+   * Get the current error information associated with this sensor.
+   */
+  virtual const Error& GetError() const;
+
+  /**
+   * @brief Clear the current error information associated with this sensor.
+   */
+  virtual void ClearError() const;
+
+  /**
+   * @brief Set error information associated with a C library call that set an
+   *        error to the "errno" global variable.
+   *
+   * @param contextMessage A custom message from the code that set the error.
+   * @param filename       Filename of the error source
+   * @param function       Function of the error source
+   * @param lineNumber     Line number of the error source
+   */
+  virtual void SetErrnoError(const wpi::Twine& contextMessage,
+                             wpi::StringRef filename, wpi::StringRef function,
+                             int lineNumber) const;
+
+  /**
+   * @brief Set the current error information associated from the nivision Imaq
+   *        API.
+   *
+   * @param success        The return from the function
+   * @param contextMessage A custom message from the code that set the error.
+   * @param filename       Filename of the error source
+   * @param function       Function of the error source
+   * @param lineNumber     Line number of the error source
+   */
+  virtual void SetImaqError(int success, const wpi::Twine& contextMessage,
+                            wpi::StringRef filename, wpi::StringRef function,
+                            int lineNumber) const;
+
+  /**
+   * @brief Set the current error information associated with this sensor.
+   *
+   * @param code           The error code
+   * @param contextMessage A custom message from the code that set the error.
+   * @param filename       Filename of the error source
+   * @param function       Function of the error source
+   * @param lineNumber     Line number of the error source
+   */
+  virtual void SetError(Error::Code code, const wpi::Twine& contextMessage,
+                        wpi::StringRef filename, wpi::StringRef function,
+                        int lineNumber) const;
+
+  /**
+   * @brief Set the current error information associated with this sensor.
+   * Range versions use for initialization code.
+   *
+   * @param code           The error code
+   * @param minRange       The minimum allowed allocation range
+   * @param maxRange       The maximum allowed allocation range
+   * @param requestedValue The requested value to allocate
+   * @param contextMessage A custom message from the code that set the error.
+   * @param filename       Filename of the error source
+   * @param function       Function of the error source
+   * @param lineNumber     Line number of the error source
+   */
+  virtual void SetErrorRange(Error::Code code, int32_t minRange,
+                             int32_t maxRange, int32_t requestedValue,
+                             const wpi::Twine& contextMessage,
+                             wpi::StringRef filename, wpi::StringRef function,
+                             int lineNumber) const;
+
+  /**
+   * @brief Set the current error information associated with this sensor.
+   *
+   * @param errorMessage   The error message from WPIErrors.h
+   * @param contextMessage A custom message from the code that set the error.
+   * @param filename       Filename of the error source
+   * @param function       Function of the error source
+   * @param lineNumber     Line number of the error source
+   */
+  virtual void SetWPIError(const wpi::Twine& errorMessage, Error::Code code,
+                           const wpi::Twine& contextMessage,
+                           wpi::StringRef filename, wpi::StringRef function,
+                           int lineNumber) const;
+
+  virtual void CloneError(const ErrorBase& rhs) const;
+
+  /**
+   * @brief Check if the current error code represents a fatal error.
+   *
+   * @return true if the current error is fatal.
+   */
+  virtual bool StatusIsFatal() const;
+
+  static void SetGlobalError(Error::Code code, const wpi::Twine& contextMessage,
+                             wpi::StringRef filename, wpi::StringRef function,
+                             int lineNumber);
+
+  static void SetGlobalWPIError(const wpi::Twine& errorMessage,
+                                const wpi::Twine& contextMessage,
+                                wpi::StringRef filename,
+                                wpi::StringRef function, int lineNumber);
+
+  /**
+   * Retrieve the last global error.
+   */
+  static Error GetGlobalError();
+
+  /**
+   * Retrieve all global errors.
+   */
+  static std::vector<Error> GetGlobalErrors();
+
+  /**
+   * Clear global errors.
+   */
+  void ClearGlobalErrors();
+
+ protected:
+  mutable Error m_error;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Filesystem.h b/wpilibc/src/main/native/include/frc/Filesystem.h
new file mode 100644
index 0000000..b7ef3f1
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Filesystem.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/SmallVector.h>
+
+namespace frc {
+/** WPILib FileSystem namespace */
+namespace filesystem {
+
+/**
+ * Obtains the current working path that the program was launched with.
+ * This is analogous to the `pwd` command on unix.
+ *
+ * @param result The result of the current working path lookup.
+ */
+void GetLaunchDirectory(wpi::SmallVectorImpl<char>& result);
+
+/**
+ * Obtains the operating directory of the program. On the roboRIO, this
+ * is /home/lvuser. In simulation, it is where the simulation was launched
+ * from (`pwd`).
+ *
+ * @param result The result of the operating directory lookup.
+ */
+void GetOperatingDirectory(wpi::SmallVectorImpl<char>& result);
+
+/**
+ * Obtains the deploy directory of the program, which is the remote location
+ * src/main/deploy is deployed to by default. On the roboRIO, this is
+ * /home/lvuser/deploy. In simulation, it is where the simulation was launched
+ * from, in the subdirectory "deploy" (`pwd`/deploy).
+ *
+ * @param result The result of the operating directory lookup
+ */
+void GetDeployDirectory(wpi::SmallVectorImpl<char>& result);
+
+}  // namespace filesystem
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/GearTooth.h b/wpilibc/src/main/native/include/frc/GearTooth.h
new file mode 100644
index 0000000..1c3df5b
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/GearTooth.h
@@ -0,0 +1,86 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <wpi/deprecated.h>
+
+#include "frc/Counter.h"
+
+namespace frc {
+
+/**
+ * Alias for counter class.
+ *
+ * Implements the gear tooth sensor supplied by FIRST. Currently there is no
+ * reverse sensing on the gear tooth sensor, but in future versions we might
+ * implement the necessary timing in the FPGA to sense direction.
+ */
+class GearTooth : public Counter {
+ public:
+  // 55 uSec for threshold
+  static constexpr double kGearToothThreshold = 55e-6;
+
+  /**
+   * Construct a GearTooth sensor given a channel.
+   *
+   * @param channel            The DIO channel that the sensor is connected to.
+   *                           0-9 are on-board, 10-25 are on the MXP.
+   * @param directionSensitive True to enable the pulse length decoding in
+   *                           hardware to specify count direction.
+   */
+  WPI_DEPRECATED(
+      "The only sensor this works with is no longer available and no teams use "
+      "it according to FMS usage reporting.")
+  explicit GearTooth(int channel, bool directionSensitive = false);
+
+  /**
+   * Construct a GearTooth sensor given a digital input.
+   *
+   * This should be used when sharing digital inputs.
+   *
+   * @param source             A pointer to the existing DigitalSource object
+   *                           (such as a DigitalInput)
+   * @param directionSensitive True to enable the pulse length decoding in
+   *                           hardware to specify count direction.
+   */
+  WPI_DEPRECATED(
+      "The only sensor this works with is no longer available and no teams use "
+      "it according to FMS usage reporting.")
+  explicit GearTooth(DigitalSource* source, bool directionSensitive = false);
+
+  /**
+   * Construct a GearTooth sensor given a digital input.
+   *
+   * This should be used when sharing digital inputs.
+   *
+   * @param source             A reference to the existing DigitalSource object
+   *                           (such as a DigitalInput)
+   * @param directionSensitive True to enable the pulse length decoding in
+   *                           hardware to specify count direction.
+   */
+  WPI_DEPRECATED(
+      "The only sensor this works with is no longer available and no teams use "
+      "it according to FMS usage reporting.")
+  explicit GearTooth(std::shared_ptr<DigitalSource> source,
+                     bool directionSensitive = false);
+
+  GearTooth(GearTooth&&) = default;
+  GearTooth& operator=(GearTooth&&) = default;
+
+  /**
+   * Common code called by the constructors.
+   */
+  void EnableDirectionSensing(bool directionSensitive);
+
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/GenericHID.h b/wpilibc/src/main/native/include/frc/GenericHID.h
new file mode 100644
index 0000000..aae10cf
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/GenericHID.h
@@ -0,0 +1,189 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <string>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+class DriverStation;
+
+/**
+ * GenericHID Interface.
+ */
+class GenericHID : public ErrorBase {
+ public:
+  enum RumbleType { kLeftRumble, kRightRumble };
+
+  enum HIDType {
+    kUnknown = -1,
+    kXInputUnknown = 0,
+    kXInputGamepad = 1,
+    kXInputWheel = 2,
+    kXInputArcadeStick = 3,
+    kXInputFlightStick = 4,
+    kXInputDancePad = 5,
+    kXInputGuitar = 6,
+    kXInputGuitar2 = 7,
+    kXInputDrumKit = 8,
+    kXInputGuitar3 = 11,
+    kXInputArcadePad = 19,
+    kHIDJoystick = 20,
+    kHIDGamepad = 21,
+    kHIDDriving = 22,
+    kHIDFlight = 23,
+    kHID1stPerson = 24
+  };
+
+  enum JoystickHand { kLeftHand = 0, kRightHand = 1 };
+
+  explicit GenericHID(int port);
+  virtual ~GenericHID() = default;
+
+  GenericHID(GenericHID&&) = default;
+  GenericHID& operator=(GenericHID&&) = default;
+
+  virtual double GetX(JoystickHand hand = kRightHand) const = 0;
+  virtual double GetY(JoystickHand hand = kRightHand) const = 0;
+
+  /**
+   * Get the button value (starting at button 1).
+   *
+   * The buttons are returned in a single 16 bit value with one bit representing
+   * the state of each button. The appropriate button is returned as a boolean
+   * value.
+   *
+   * @param button The button number to be read (starting at 1)
+   * @return The state of the button.
+   */
+  bool GetRawButton(int button) const;
+
+  /**
+   * Whether the button was pressed since the last check. Button indexes begin
+   * at 1.
+   *
+   * @param button The button index, beginning at 1.
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetRawButtonPressed(int button);
+
+  /**
+   * Whether the button was released since the last check. Button indexes begin
+   * at 1.
+   *
+   * @param button The button index, beginning at 1.
+   * @return Whether the button was released since the last check.
+   */
+  bool GetRawButtonReleased(int button);
+
+  /**
+   * Get the value of the axis.
+   *
+   * @param axis The axis to read, starting at 0.
+   * @return The value of the axis.
+   */
+  double GetRawAxis(int axis) const;
+
+  /**
+   * Get the angle in degrees of a POV on the HID.
+   *
+   * The POV angles start at 0 in the up direction, and increase clockwise
+   * (e.g. right is 90, upper-left is 315).
+   *
+   * @param pov The index of the POV to read (starting at 0)
+   * @return the angle of the POV in degrees, or -1 if the POV is not pressed.
+   */
+  int GetPOV(int pov = 0) const;
+
+  /**
+   * Get the number of axes for the HID.
+   *
+   * @return the number of axis for the current HID
+   */
+  int GetAxisCount() const;
+
+  /**
+   * Get the number of POVs for the HID.
+   *
+   * @return the number of POVs for the current HID
+   */
+  int GetPOVCount() const;
+
+  /**
+   * Get the number of buttons for the HID.
+   *
+   * @return the number of buttons on the current HID
+   */
+  int GetButtonCount() const;
+
+  /**
+   * Get the type of the HID.
+   *
+   * @return the type of the HID.
+   */
+  GenericHID::HIDType GetType() const;
+
+  /**
+   * Get the name of the HID.
+   *
+   * @return the name of the HID.
+   */
+  std::string GetName() const;
+
+  /**
+   * Get the axis type of a joystick axis.
+   *
+   * @return the axis type of a joystick axis.
+   */
+  int GetAxisType(int axis) const;
+
+  /**
+   * Get the port number of the HID.
+   *
+   * @return The port number of the HID.
+   */
+  int GetPort() const;
+
+  /**
+   * Set a single HID output value for the HID.
+   *
+   * @param outputNumber The index of the output to set (1-32)
+   * @param value        The value to set the output to
+   */
+  void SetOutput(int outputNumber, bool value);
+
+  /**
+   * Set all output values for the HID.
+   *
+   * @param value The 32 bit output value (1 bit for each output)
+   */
+  void SetOutputs(int value);
+
+  /**
+   * Set the rumble output for the HID.
+   *
+   * The DS currently supports 2 rumble values, left rumble and right rumble.
+   *
+   * @param type  Which rumble value to set
+   * @param value The normalized value (0 to 1) to set the rumble to
+   */
+  void SetRumble(RumbleType type, double value);
+
+ private:
+  DriverStation* m_ds;
+  int m_port;
+  int m_outputs = 0;
+  uint16_t m_leftRumble = 0;
+  uint16_t m_rightRumble = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/GyroBase.h b/wpilibc/src/main/native/include/frc/GyroBase.h
new file mode 100644
index 0000000..037686f
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/GyroBase.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/ErrorBase.h"
+#include "frc/PIDSource.h"
+#include "frc/interfaces/Gyro.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+/**
+ * GyroBase is the common base class for Gyro implementations such as
+ * AnalogGyro.
+ */
+class GyroBase : public Gyro,
+                 public ErrorBase,
+                 public PIDSource,
+                 public Sendable,
+                 public SendableHelper<GyroBase> {
+ public:
+  GyroBase() = default;
+  GyroBase(GyroBase&&) = default;
+  GyroBase& operator=(GyroBase&&) = default;
+
+  // PIDSource interface
+  /**
+   * Get the PIDOutput for the PIDSource base object. Can be set to return
+   * angle or rate using SetPIDSourceType(). Defaults to angle.
+   *
+   * @return The PIDOutput (angle or rate, defaults to angle)
+   */
+  double PIDGet() override;
+
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/I2C.h b/wpilibc/src/main/native/include/frc/I2C.h
new file mode 100644
index 0000000..2f12615
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/I2C.h
@@ -0,0 +1,144 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <hal/I2CTypes.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+/**
+ * I2C bus interface class.
+ *
+ * This class is intended to be used by sensor (and other I2C device) drivers.
+ * It probably should not be used directly.
+ */
+class I2C : public ErrorBase {
+ public:
+  enum Port { kOnboard = 0, kMXP };
+
+  /**
+   * Constructor.
+   *
+   * @param port          The I2C port to which the device is connected.
+   * @param deviceAddress The address of the device on the I2C bus.
+   */
+  I2C(Port port, int deviceAddress);
+
+  ~I2C() override;
+
+  I2C(I2C&&) = default;
+  I2C& operator=(I2C&&) = default;
+
+  /**
+   * Generic transaction.
+   *
+   * This is a lower-level interface to the I2C hardware giving you more control
+   * over each transaction. If you intend to write multiple bytes in the same
+   * transaction and do not plan to receive anything back, use writeBulk()
+   * instead. Calling this with a receiveSize of 0 will result in an error.
+   *
+   * @param dataToSend   Buffer of data to send as part of the transaction.
+   * @param sendSize     Number of bytes to send as part of the transaction.
+   * @param dataReceived Buffer to read data into.
+   * @param receiveSize  Number of bytes to read from the device.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  bool Transaction(uint8_t* dataToSend, int sendSize, uint8_t* dataReceived,
+                   int receiveSize);
+
+  /**
+   * Attempt to address a device on the I2C bus.
+   *
+   * This allows you to figure out if there is a device on the I2C bus that
+   * responds to the address specified in the constructor.
+   *
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  bool AddressOnly();
+
+  /**
+   * Execute a write transaction with the device.
+   *
+   * Write a single byte to a register on a device and wait until the
+   *   transaction is complete.
+   *
+   * @param registerAddress The address of the register on the device to be
+   *                        written.
+   * @param data            The byte to write to the register on the device.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  bool Write(int registerAddress, uint8_t data);
+
+  /**
+   * Execute a bulk write transaction with the device.
+   *
+   * Write multiple bytes to a device and wait until the
+   *   transaction is complete.
+   *
+   * @param data  The data to write to the register on the device.
+   * @param count The number of bytes to be written.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  bool WriteBulk(uint8_t* data, int count);
+
+  /**
+   * Execute a read transaction with the device.
+   *
+   * Read bytes from a device.
+   * Most I2C devices will auto-increment the register pointer internally
+   * allowing you to read consecutive registers on a device in a single
+   * transaction.
+   *
+   * @param registerAddress The register to read first in the transaction.
+   * @param count           The number of bytes to read in the transaction.
+   * @param buffer          A pointer to the array of bytes to store the data
+   *                        read from the device.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  bool Read(int registerAddress, int count, uint8_t* data);
+
+  /**
+   * Execute a read only transaction with the device.
+   *
+   * Read bytes from a device. This method does not write any data to prompt the
+   * device.
+   *
+   * @param buffer A pointer to the array of bytes to store the data read from
+   *               the device.
+   * @param count  The number of bytes to read in the transaction.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  bool ReadOnly(int count, uint8_t* buffer);
+
+  /**
+   * Verify that a device's registers contain expected values.
+   *
+   * Most devices will have a set of registers that contain a known value that
+   * can be used to identify them.  This allows an I2C device driver to easily
+   * verify that the device contains the expected value.
+   *
+   * @pre The device must support and be configured to use register
+   * auto-increment.
+   *
+   * @param registerAddress The base register to start reading from the device.
+   * @param count           The size of the field to be verified.
+   * @param expected        A buffer containing the values expected from the
+   *                        device.
+   */
+  bool VerifySensor(int registerAddress, int count, const uint8_t* expected);
+
+ private:
+  hal::I2CPort m_port;
+  int m_deviceAddress;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/InterruptableSensorBase.h b/wpilibc/src/main/native/include/frc/InterruptableSensorBase.h
new file mode 100644
index 0000000..8c2a564
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/InterruptableSensorBase.h
@@ -0,0 +1,152 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+#include <memory>
+
+#include <hal/Interrupts.h>
+
+#include "frc/AnalogTriggerType.h"
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+class InterruptableSensorBase : public ErrorBase {
+ public:
+  enum WaitResult {
+    kTimeout = 0x0,
+    kRisingEdge = 0x1,
+    kFallingEdge = 0x100,
+    kBoth = 0x101,
+  };
+
+  /**
+   * Handler for interrupts.
+   *
+   * First parameter is if rising, 2nd is if falling.
+   */
+  using InterruptEventHandler = std::function<void(WaitResult)>;
+
+  InterruptableSensorBase() = default;
+
+  /**
+   * Free the resources for an interrupt event.
+   */
+  virtual ~InterruptableSensorBase();
+
+  InterruptableSensorBase(InterruptableSensorBase&&) = default;
+  InterruptableSensorBase& operator=(InterruptableSensorBase&&) = default;
+
+  virtual HAL_Handle GetPortHandleForRouting() const = 0;
+  virtual AnalogTriggerType GetAnalogTriggerTypeForRouting() const = 0;
+
+  /**
+   * Request one of the 8 interrupts asynchronously on this digital input.
+   *
+   * Request interrupts in asynchronous mode where the user's interrupt handler
+   * will be called when the interrupt fires. Users that want control over the
+   * thread priority should use the synchronous method with their own spawned
+   * thread. The default is interrupt on rising edges only.
+   */
+  virtual void RequestInterrupts(HAL_InterruptHandlerFunction handler,
+                                 void* param);
+
+  /**
+   * Request one of the 8 interrupts asynchronously on this digital input.
+   *
+   * Request interrupts in asynchronous mode where the user's interrupt handler
+   * will be called when the interrupt fires. Users that want control over the
+   * thread priority should use the synchronous method with their own spawned
+   * thread. The default is interrupt on rising edges only.
+   */
+  virtual void RequestInterrupts(InterruptEventHandler handler);
+
+  /**
+   * Request one of the 8 interrupts synchronously on this digital input.
+   *
+   * Request interrupts in synchronous mode where the user program will have to
+   * explicitly wait for the interrupt to occur using WaitForInterrupt.
+   * The default is interrupt on rising edges only.
+   */
+  virtual void RequestInterrupts();
+
+  /**
+   * Cancel interrupts on this device.
+   *
+   * This deallocates all the chipobject structures and disables any interrupts.
+   */
+  virtual void CancelInterrupts();
+
+  /**
+   * In synchronous mode, wait for the defined interrupt to occur.
+   *
+   * You should <b>NOT</b> attempt to read the sensor from another thread while
+   * waiting for an interrupt. This is not threadsafe, and can cause memory
+   * corruption
+   *
+   * @param timeout        Timeout in seconds
+   * @param ignorePrevious If true, ignore interrupts that happened before
+   *                       WaitForInterrupt was called.
+   * @return What interrupts fired
+   */
+  virtual WaitResult WaitForInterrupt(double timeout,
+                                      bool ignorePrevious = true);
+
+  /**
+   * Enable interrupts to occur on this input.
+   *
+   * Interrupts are disabled when the RequestInterrupt call is made. This gives
+   * time to do the setup of the other options before starting to field
+   * interrupts.
+   */
+  virtual void EnableInterrupts();
+
+  /**
+   * Disable Interrupts without without deallocating structures.
+   */
+  virtual void DisableInterrupts();
+
+  /**
+   * Return the timestamp for the rising interrupt that occurred most recently.
+   *
+   * This is in the same time domain as GetClock().
+   * The rising-edge interrupt should be enabled with
+   * {@link #DigitalInput.SetUpSourceEdge}
+   *
+   * @return Timestamp in seconds since boot.
+   */
+  virtual double ReadRisingTimestamp();
+
+  /**
+   * Return the timestamp for the falling interrupt that occurred most recently.
+   *
+   * This is in the same time domain as GetClock().
+   * The falling-edge interrupt should be enabled with
+   * {@link #DigitalInput.SetUpSourceEdge}
+   *
+   * @return Timestamp in seconds since boot.
+   */
+  virtual double ReadFallingTimestamp();
+
+  /**
+   * Set which edge to trigger interrupts on
+   *
+   * @param risingEdge  true to interrupt on rising edge
+   * @param fallingEdge true to interrupt on falling edge
+   */
+  virtual void SetUpSourceEdge(bool risingEdge, bool fallingEdge);
+
+ protected:
+  hal::Handle<HAL_InterruptHandle> m_interrupt;
+  std::unique_ptr<InterruptEventHandler> m_interruptHandler{nullptr};
+
+  void AllocateInterrupts(bool watcher);
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/IterativeRobot.h b/wpilibc/src/main/native/include/frc/IterativeRobot.h
new file mode 100644
index 0000000..447c477
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/IterativeRobot.h
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+
+#include "frc/IterativeRobotBase.h"
+
+namespace frc {
+
+/**
+ * IterativeRobot implements the IterativeRobotBase robot program framework.
+ *
+ * The IterativeRobot class is intended to be subclassed by a user creating a
+ * robot program.
+ *
+ * Periodic() functions from the base class are called each time a new packet is
+ * received from the driver station.
+ */
+class IterativeRobot : public IterativeRobotBase {
+ public:
+  WPI_DEPRECATED(
+      "Use TimedRobot instead. It's a drop-in replacement that provides more "
+      "regular execution periods.")
+  IterativeRobot();
+  virtual ~IterativeRobot() = default;
+
+  /**
+   * Provide an alternate "main loop" via StartCompetition().
+   *
+   * This specific StartCompetition() implements "main loop" behaviour synced
+   * with the DS packets.
+   */
+  void StartCompetition() override;
+
+  /**
+   * Ends the main loop in StartCompetition().
+   */
+  void EndCompetition() override;
+
+ private:
+  std::atomic<bool> m_exit{false};
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/IterativeRobotBase.h b/wpilibc/src/main/native/include/frc/IterativeRobotBase.h
new file mode 100644
index 0000000..b78765a
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/IterativeRobotBase.h
@@ -0,0 +1,175 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+#include <wpi/deprecated.h>
+
+#include "frc/RobotBase.h"
+#include "frc/Watchdog.h"
+
+namespace frc {
+
+/**
+ * IterativeRobotBase implements a specific type of robot program framework,
+ * extending the RobotBase class.
+ *
+ * The IterativeRobotBase class does not implement StartCompetition(), so it
+ * should not be used by teams directly.
+ *
+ * This class provides the following functions which are called by the main
+ * loop, StartCompetition(), at the appropriate times:
+ *
+ * RobotInit() -- provide for initialization at robot power-on
+ *
+ * Init() functions -- each of the following functions is called once when the
+ *                     appropriate mode is entered:
+ *   - DisabledInit()   -- called each and every time disabled is entered from
+ *                         another mode
+ *   - AutonomousInit() -- called each and every time autonomous is entered from
+ *                         another mode
+ *   - TeleopInit()     -- called each and every time teleop is entered from
+ *                         another mode
+ *   - TestInit()       -- called each and every time test is entered from
+ *                         another mode
+ *
+ * Periodic() functions -- each of these functions is called on an interval:
+ *   - RobotPeriodic()
+ *   - DisabledPeriodic()
+ *   - AutonomousPeriodic()
+ *   - TeleopPeriodic()
+ *   - TestPeriodic()
+ */
+class IterativeRobotBase : public RobotBase {
+ public:
+  /**
+   * Robot-wide initialization code should go here.
+   *
+   * Users should override this method for default Robot-wide initialization
+   * which will be called when the robot is first powered on. It will be called
+   * exactly one time.
+   *
+   * Warning: the Driver Station "Robot Code" light and FMS "Robot Ready"
+   * indicators will be off until RobotInit() exits. Code in RobotInit() that
+   * waits for enable will cause the robot to never indicate that the code is
+   * ready, causing the robot to be bypassed in a match.
+   */
+  virtual void RobotInit();
+
+  /**
+   * Initialization code for disabled mode should go here.
+   *
+   * Users should override this method for initialization code which will be
+   * called each time
+   * the robot enters disabled mode.
+   */
+  virtual void DisabledInit();
+
+  /**
+   * Initialization code for autonomous mode should go here.
+   *
+   * Users should override this method for initialization code which will be
+   * called each time the robot enters autonomous mode.
+   */
+  virtual void AutonomousInit();
+
+  /**
+   * Initialization code for teleop mode should go here.
+   *
+   * Users should override this method for initialization code which will be
+   * called each time the robot enters teleop mode.
+   */
+  virtual void TeleopInit();
+
+  /**
+   * Initialization code for test mode should go here.
+   *
+   * Users should override this method for initialization code which will be
+   * called each time the robot enters test mode.
+   */
+  virtual void TestInit();
+
+  /**
+   * Periodic code for all modes should go here.
+   *
+   * This function is called each time a new packet is received from the driver
+   * station.
+   */
+  virtual void RobotPeriodic();
+
+  /**
+   * Periodic code for disabled mode should go here.
+   *
+   * Users should override this method for code which will be called each time a
+   * new packet is received from the driver station and the robot is in disabled
+   * mode.
+   */
+  virtual void DisabledPeriodic();
+
+  /**
+   * Periodic code for autonomous mode should go here.
+   *
+   * Users should override this method for code which will be called each time a
+   * new packet is received from the driver station and the robot is in
+   * autonomous mode.
+   */
+  virtual void AutonomousPeriodic();
+
+  /**
+   * Periodic code for teleop mode should go here.
+   *
+   * Users should override this method for code which will be called each time a
+   * new packet is received from the driver station and the robot is in teleop
+   * mode.
+   */
+  virtual void TeleopPeriodic();
+
+  /**
+   * Periodic code for test mode should go here.
+   *
+   * Users should override this method for code which will be called each time a
+   * new packet is received from the driver station and the robot is in test
+   * mode.
+   */
+  virtual void TestPeriodic();
+
+ protected:
+  /**
+   * Constructor for IterativeRobotBase.
+   *
+   * @param period Period in seconds.
+   */
+  WPI_DEPRECATED("Use ctor with unit-safety instead.")
+  explicit IterativeRobotBase(double period);
+
+  /**
+   * Constructor for IterativeRobotBase.
+   *
+   * @param period Period.
+   */
+  explicit IterativeRobotBase(units::second_t period);
+
+  virtual ~IterativeRobotBase() = default;
+
+  IterativeRobotBase(IterativeRobotBase&&) = default;
+  IterativeRobotBase& operator=(IterativeRobotBase&&) = default;
+
+  void LoopFunc();
+
+  units::second_t m_period;
+
+ private:
+  enum class Mode { kNone, kDisabled, kAutonomous, kTeleop, kTest };
+
+  Mode m_lastMode = Mode::kNone;
+  Watchdog m_watchdog;
+
+  void PrintLoopOverrunMessage();
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Jaguar.h b/wpilibc/src/main/native/include/frc/Jaguar.h
new file mode 100644
index 0000000..7a8503e
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Jaguar.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Luminary Micro / Vex Robotics Jaguar Speed Controller with PWM control.
+ *
+ * Note that the Jaguar uses the following bounds for PWM values. These values
+ * should work reasonably well for most controllers, but if users experience
+ * issues such as asymmetric behavior around the deadband or inability to
+ * saturate the controller in either direction, calibration is recommended. The
+ * calibration procedure can be found in the Jaguar User Manual available from
+ * Vex.
+ *
+ * \li 2.310ms = full "forward"
+ * \li 1.550ms = the "high end" of the deadband range
+ * \li 1.507ms = center of the deadband range (off)
+ * \li 1.454ms = the "low end" of the deadband range
+ * \li 0.697ms = full "reverse"
+ */
+class Jaguar : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a Jaguar connected via PWM.
+   *
+   * @param channel The PWM channel that the Jaguar is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit Jaguar(int channel);
+
+  Jaguar(Jaguar&&) = default;
+  Jaguar& operator=(Jaguar&&) = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Joystick.h b/wpilibc/src/main/native/include/frc/Joystick.h
new file mode 100644
index 0000000..4ae398c
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Joystick.h
@@ -0,0 +1,244 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <array>
+
+#include <wpi/deprecated.h>
+
+#include "frc/GenericHID.h"
+
+namespace frc {
+
+/**
+ * Handle input from standard Joysticks connected to the Driver Station.
+ *
+ * This class handles standard input that comes from the Driver Station. Each
+ * time a value is requested the most recent value is returned. There is a
+ * single class instance for each joystick and the mapping of ports to hardware
+ * buttons depends on the code in the Driver Station.
+ */
+class Joystick : public GenericHID {
+ public:
+  static constexpr int kDefaultXChannel = 0;
+  static constexpr int kDefaultYChannel = 1;
+  static constexpr int kDefaultZChannel = 2;
+  static constexpr int kDefaultTwistChannel = 2;
+  static constexpr int kDefaultThrottleChannel = 3;
+
+  enum AxisType { kXAxis, kYAxis, kZAxis, kTwistAxis, kThrottleAxis };
+  enum ButtonType { kTriggerButton, kTopButton };
+
+  /**
+   * Construct an instance of a joystick.
+   *
+   * The joystick index is the USB port on the Driver Station.
+   *
+   * @param port The port on the Driver Station that the joystick is plugged
+   *             into (0-5).
+   */
+  explicit Joystick(int port);
+
+  virtual ~Joystick() = default;
+
+  Joystick(Joystick&&) = default;
+  Joystick& operator=(Joystick&&) = default;
+
+  /**
+   * Set the channel associated with the X axis.
+   *
+   * @param channel The channel to set the axis to.
+   */
+  void SetXChannel(int channel);
+
+  /**
+   * Set the channel associated with the Y axis.
+   *
+   * @param axis    The axis to set the channel for.
+   * @param channel The channel to set the axis to.
+   */
+  void SetYChannel(int channel);
+
+  /**
+   * Set the channel associated with the Z axis.
+   *
+   * @param axis    The axis to set the channel for.
+   * @param channel The channel to set the axis to.
+   */
+  void SetZChannel(int channel);
+
+  /**
+   * Set the channel associated with the twist axis.
+   *
+   * @param axis    The axis to set the channel for.
+   * @param channel The channel to set the axis to.
+   */
+  void SetTwistChannel(int channel);
+
+  /**
+   * Set the channel associated with the throttle axis.
+   *
+   * @param axis    The axis to set the channel for.
+   * @param channel The channel to set the axis to.
+   */
+  void SetThrottleChannel(int channel);
+
+  /**
+   * Get the channel currently associated with the X axis.
+   *
+   * @return The channel for the axis.
+   */
+  int GetXChannel() const;
+
+  /**
+   * Get the channel currently associated with the Y axis.
+   *
+   * @return The channel for the axis.
+   */
+  int GetYChannel() const;
+
+  /**
+   * Get the channel currently associated with the Z axis.
+   *
+   * @return The channel for the axis.
+   */
+  int GetZChannel() const;
+
+  /**
+   * Get the channel currently associated with the twist axis.
+   *
+   * @return The channel for the axis.
+   */
+  int GetTwistChannel() const;
+
+  /**
+   * Get the channel currently associated with the throttle axis.
+   *
+   * @return The channel for the axis.
+   */
+  int GetThrottleChannel() const;
+
+  /**
+   * Get the X value of the joystick.
+   *
+   * This depends on the mapping of the joystick connected to the current port.
+   *
+   * @param hand This parameter is ignored for the Joystick class and is only
+   *             here to complete the GenericHID interface.
+   */
+  double GetX(JoystickHand hand = kRightHand) const override;
+
+  /**
+   * Get the Y value of the joystick.
+   *
+   * This depends on the mapping of the joystick connected to the current port.
+   *
+   * @param hand This parameter is ignored for the Joystick class and is only
+   *             here to complete the GenericHID interface.
+   */
+  double GetY(JoystickHand hand = kRightHand) const override;
+
+  /**
+   * Get the Z value of the current joystick.
+   *
+   * This depends on the mapping of the joystick connected to the current port.
+   */
+  double GetZ() const;
+
+  /**
+   * Get the twist value of the current joystick.
+   *
+   * This depends on the mapping of the joystick connected to the current port.
+   */
+  double GetTwist() const;
+
+  /**
+   * Get the throttle value of the current joystick.
+   *
+   * This depends on the mapping of the joystick connected to the current port.
+   */
+  double GetThrottle() const;
+
+  /**
+   * Read the state of the trigger on the joystick.
+   *
+   * Look up which button has been assigned to the trigger and read its state.
+   *
+   * @return The state of the trigger.
+   */
+  bool GetTrigger() const;
+
+  /**
+   * Whether the trigger was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetTriggerPressed();
+
+  /**
+   * Whether the trigger was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetTriggerReleased();
+
+  /**
+   * Read the state of the top button on the joystick.
+   *
+   * Look up which button has been assigned to the top and read its state.
+   *
+   * @return The state of the top button.
+   */
+  bool GetTop() const;
+
+  /**
+   * Whether the top button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetTopPressed();
+
+  /**
+   * Whether the top button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetTopReleased();
+
+  /**
+   * Get the magnitude of the direction vector formed by the joystick's
+   * current position relative to its origin.
+   *
+   * @return The magnitude of the direction vector
+   */
+  double GetMagnitude() const;
+
+  /**
+   * Get the direction of the vector formed by the joystick and its origin
+   * in radians.
+   *
+   * @return The direction of the vector in radians
+   */
+  double GetDirectionRadians() const;
+
+  /**
+   * Get the direction of the vector formed by the joystick and its origin
+   * in degrees.
+   *
+   * @return The direction of the vector in degrees
+   */
+  double GetDirectionDegrees() const;
+
+ private:
+  enum Axis { kX, kY, kZ, kTwist, kThrottle, kNumAxes };
+  enum Button { kTrigger = 1, kTop = 2 };
+
+  std::array<int, Axis::kNumAxes> m_axes;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/LinearFilter.h b/wpilibc/src/main/native/include/frc/LinearFilter.h
new file mode 100644
index 0000000..2b83a32
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/LinearFilter.h
@@ -0,0 +1,194 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <cassert>
+#include <cmath>
+#include <initializer_list>
+#include <vector>
+
+#include <hal/FRCUsageReporting.h>
+#include <units/units.h>
+#include <wpi/ArrayRef.h>
+#include <wpi/circular_buffer.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, we highly recommend the following articles:<br>
+ * https://en.wikipedia.org/wiki/Linear_filter<br>
+ * https://en.wikipedia.org/wiki/Iir_filter<br>
+ * https://en.wikipedia.org/wiki/Fir_filter<br>
+ *
+ * Note 1: Calculate() should be called by the user on a known, regular period.
+ * You can use a Notifier for this 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 Calculate() gets called at the desired, constant frequency!
+ */
+template <class T>
+class LinearFilter {
+ public:
+  /**
+   * Create a linear FIR or IIR filter.
+   *
+   * @param ffGains The "feed forward" or FIR gains.
+   * @param fbGains The "feed back" or IIR gains.
+   */
+  LinearFilter(wpi::ArrayRef<double> ffGains, wpi::ArrayRef<double> fbGains)
+      : m_inputs(ffGains.size()),
+        m_outputs(fbGains.size()),
+        m_inputGains(ffGains),
+        m_outputGains(fbGains) {
+    static int instances = 0;
+    instances++;
+    HAL_Report(HALUsageReporting::kResourceType_LinearFilter, instances);
+  }
+
+  /**
+   * Create a linear FIR or IIR filter.
+   *
+   * @param ffGains The "feed forward" or FIR gains.
+   * @param fbGains The "feed back" or IIR gains.
+   */
+  LinearFilter(std::initializer_list<double> ffGains,
+               std::initializer_list<double> fbGains)
+      : LinearFilter(wpi::makeArrayRef(ffGains.begin(), ffGains.end()),
+                     wpi::makeArrayRef(fbGains.begin(), fbGains.end())) {}
+
+  // Static methods to create commonly used filters
+  /**
+   * Creates a one-pole IIR low-pass filter of the form:<br>
+   *   y[n] = (1 - gain) * x[n] + gain * y[n-1]<br>
+   * where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
+   *
+   * This filter is stable for time constants greater than zero.
+   *
+   * @param timeConstant The discrete-time time constant in seconds.
+   * @param period       The period in seconds between samples taken by the
+   *                     user.
+   */
+  static LinearFilter<T> SinglePoleIIR(double timeConstant,
+                                       units::second_t period) {
+    double gain = std::exp(-period.to<double>() / timeConstant);
+    return LinearFilter(1.0 - gain, -gain);
+  }
+
+  /**
+   * Creates a first-order high-pass filter of the form:<br>
+   *   y[n] = gain * x[n] + (-gain) * x[n-1] + gain * y[n-1]<br>
+   * where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
+   *
+   * This filter is stable for time constants greater than zero.
+   *
+   * @param timeConstant The discrete-time time constant in seconds.
+   * @param period       The period in seconds between samples taken by the
+   *                     user.
+   */
+  static LinearFilter<T> HighPass(double timeConstant, units::second_t period) {
+    double gain = std::exp(-period.to<double>() / timeConstant);
+    return LinearFilter({gain, -gain}, {-gain});
+  }
+
+  /**
+   * Creates a K-tap FIR moving average filter of the form:<br>
+   *   y[n] = 1/k * (x[k] + x[k-1] + … + x[0])
+   *
+   * This filter is always stable.
+   *
+   * @param taps The number of samples to average over. Higher = smoother but
+   *             slower
+   */
+  static LinearFilter<T> MovingAverage(int taps) {
+    assert(taps > 0);
+
+    std::vector<double> gains(taps, 1.0 / taps);
+    return LinearFilter(gains, {});
+  }
+
+  /**
+   * Reset the filter state.
+   */
+  void Reset() {
+    m_inputs.reset();
+    m_outputs.reset();
+  }
+
+  /**
+   * Calculates the next value of the filter.
+   *
+   * @param input Current input value.
+   *
+   * @return The filtered value at this step
+   */
+  T Calculate(T input) {
+    T retVal = T(0.0);
+
+    // Rotate the inputs
+    m_inputs.push_front(input);
+
+    // Calculate the new value
+    for (size_t i = 0; i < m_inputGains.size(); i++) {
+      retVal += m_inputs[i] * m_inputGains[i];
+    }
+    for (size_t i = 0; i < m_outputGains.size(); i++) {
+      retVal -= m_outputs[i] * m_outputGains[i];
+    }
+
+    // Rotate the outputs
+    m_outputs.push_front(retVal);
+
+    return retVal;
+  }
+
+ private:
+  wpi::circular_buffer<T> m_inputs;
+  wpi::circular_buffer<T> m_outputs;
+  std::vector<double> m_inputGains;
+  std::vector<double> m_outputGains;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/MedianFilter.h b/wpilibc/src/main/native/include/frc/MedianFilter.h
new file mode 100644
index 0000000..b5d499b
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/MedianFilter.h
@@ -0,0 +1,80 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared 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 <vector>
+
+#include <wpi/Algorithm.h>
+#include <wpi/circular_buffer.h>
+
+namespace frc {
+/**
+ * A class that implements a moving-window median filter.  Useful for reducing
+ * measurement noise, especially with processes that generate occasional,
+ * extreme outliers (such as values from vision processing, LIDAR, or ultrasonic
+ * sensors).
+ */
+template <class T>
+class MedianFilter {
+ public:
+  /**
+   * Creates a new MedianFilter.
+   *
+   * @param size The number of samples in the moving window.
+   */
+  explicit MedianFilter(size_t size) : m_valueBuffer(size), m_size{size} {}
+
+  /**
+   * Calculates the moving-window median for the next value of the input stream.
+   *
+   * @param next The next input value.
+   * @return The median of the moving window, updated to include the next value.
+   */
+  T Calculate(T next) {
+    // Insert next value at proper point in sorted array
+    wpi::insert_sorted(m_orderedValues, next);
+
+    size_t curSize = m_orderedValues.size();
+
+    // If buffer is at max size, pop element off of end of circular buffer
+    // and remove from ordered list
+    if (curSize > m_size) {
+      m_orderedValues.erase(std::find(m_orderedValues.begin(),
+                                      m_orderedValues.end(),
+                                      m_valueBuffer.pop_back()));
+      curSize = curSize - 1;
+    }
+
+    // Add next value to circular buffer
+    m_valueBuffer.push_front(next);
+
+    if (curSize % 2 == 1) {
+      // If size is odd, return middle element of sorted list
+      return m_orderedValues[curSize / 2];
+    } else {
+      // If size is even, return average of middle elements
+      return (m_orderedValues[curSize / 2 - 1] + m_orderedValues[curSize / 2]) /
+             2.0;
+    }
+  }
+
+  /**
+   * Resets the filter, clearing the window of all elements.
+   */
+  void Reset() {
+    m_orderedValues.clear();
+    m_valueBuffer.reset();
+  }
+
+ private:
+  wpi::circular_buffer<T> m_valueBuffer;
+  std::vector<T> m_orderedValues;
+  size_t m_size;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/MotorSafety.h b/wpilibc/src/main/native/include/frc/MotorSafety.h
new file mode 100644
index 0000000..afd0853
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/MotorSafety.h
@@ -0,0 +1,113 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/mutex.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/Timer.h"
+
+namespace frc {
+
+/**
+ * This base class runs a watchdog timer and calls the subclass's StopMotor()
+ * function if the timeout expires.
+ *
+ * The subclass should call Feed() whenever the motor value is updated.
+ */
+class MotorSafety : public ErrorBase {
+ public:
+  MotorSafety();
+  virtual ~MotorSafety();
+
+  MotorSafety(MotorSafety&& rhs);
+  MotorSafety& operator=(MotorSafety&& rhs);
+
+  /**
+   * Feed the motor safety object.
+   *
+   * Resets the timer on this object that is used to do the timeouts.
+   */
+  void Feed();
+
+  /**
+   * Set the expiration time for the corresponding motor safety object.
+   *
+   * @param expirationTime The timeout value in seconds.
+   */
+  void SetExpiration(double expirationTime);
+
+  /**
+   * Retrieve the timeout value for the corresponding motor safety object.
+   *
+   * @return the timeout value in seconds.
+   */
+  double GetExpiration() const;
+
+  /**
+   * Determine if the motor is still operating or has timed out.
+   *
+   * @return true if the motor is still operating normally and hasn't timed out.
+   */
+  bool IsAlive() const;
+
+  /**
+   * Enable/disable motor safety for this device.
+   *
+   * Turn on and off the motor safety option for this PWM object.
+   *
+   * @param enabled True if motor safety is enforced for this object.
+   */
+  void SetSafetyEnabled(bool enabled);
+
+  /**
+   * Return the state of the motor safety enabled flag.
+   *
+   * Return if the motor safety is currently enabled for this device.
+   *
+   * @return True if motor safety is enforced for this device.
+   */
+  bool IsSafetyEnabled() const;
+
+  /**
+   * Check if this motor has exceeded its timeout.
+   *
+   * This method is called periodically to determine if this motor has exceeded
+   * its timeout value. If it has, the stop method is called, and the motor is
+   * shut down until its value is updated again.
+   */
+  void Check();
+
+  /**
+   * Check the motors to see if any have timed out.
+   *
+   * This static method is called periodically to poll all the motors and stop
+   * any that have timed out.
+   */
+  static void CheckMotors();
+
+  virtual void StopMotor() = 0;
+  virtual void GetDescription(wpi::raw_ostream& desc) const = 0;
+
+ private:
+  static constexpr double kDefaultSafetyExpiration = 0.1;
+
+  // The expiration time for this object
+  double m_expiration = kDefaultSafetyExpiration;
+
+  // True if motor safety is enabled for this motor
+  bool m_enabled = false;
+
+  // The FPGA clock value when the motor has expired
+  double m_stopTime = Timer::GetFPGATimestamp();
+
+  mutable wpi::mutex m_thisMutex;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/NidecBrushless.h b/wpilibc/src/main/native/include/frc/NidecBrushless.h
new file mode 100644
index 0000000..fa77e28
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/NidecBrushless.h
@@ -0,0 +1,109 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/DigitalOutput.h"
+#include "frc/ErrorBase.h"
+#include "frc/MotorSafety.h"
+#include "frc/PWM.h"
+#include "frc/SpeedController.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+
+/**
+ * Nidec Brushless Motor.
+ */
+class NidecBrushless : public SpeedController,
+                       public MotorSafety,
+                       public Sendable,
+                       public SendableHelper<NidecBrushless> {
+ public:
+  /**
+   * Constructor.
+   *
+   * @param pwmChannel The PWM channel that the Nidec Brushless controller is
+   *                   attached to. 0-9 are on-board, 10-19 are on the MXP port.
+   * @param dioChannel The DIO channel that the Nidec Brushless controller is
+   *                   attached to. 0-9 are on-board, 10-25 are on the MXP port.
+   */
+  NidecBrushless(int pwmChannel, int dioChannel);
+
+  ~NidecBrushless() override = default;
+
+  NidecBrushless(NidecBrushless&&) = default;
+  NidecBrushless& operator=(NidecBrushless&&) = default;
+
+  // SpeedController interface
+  /**
+   * Set the PWM value.
+   *
+   * The PWM value is set using a range of -1.0 to 1.0, appropriately scaling
+   * the value for the FPGA.
+   *
+   * @param speed The speed value between -1.0 and 1.0 to set.
+   */
+  void Set(double speed) override;
+
+  /**
+   * Get the recently set value of the PWM.
+   *
+   * @return The most recently set value for the PWM between -1.0 and 1.0.
+   */
+  double Get() const override;
+
+  void SetInverted(bool isInverted) override;
+
+  bool GetInverted() const override;
+
+  /**
+   * Disable the motor. The Enable() function must be called to re-enable the
+   * motor.
+   */
+  void Disable() override;
+
+  /**
+   * Re-enable the motor after Disable() has been called. The Set() function
+   * must be called to set a new motor speed.
+   */
+  void Enable();
+
+  // PIDOutput interface
+  /**
+   * Write out the PID value as seen in the PIDOutput base object.
+   *
+   * @param output Write out the PWM value as was found in the PIDController
+   */
+  void PIDWrite(double output) override;
+
+  // MotorSafety interface
+  void StopMotor() override;
+  void GetDescription(wpi::raw_ostream& desc) const override;
+
+  /**
+   * Gets the channel number associated with the object.
+   *
+   * @return The channel number.
+   */
+  int GetChannel() const;
+
+  // Sendable interface
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  bool m_isInverted = false;
+  bool m_disabled = false;
+  DigitalOutput m_dio;
+  PWM m_pwm;
+  double m_speed = 0.0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Notifier.h b/wpilibc/src/main/native/include/frc/Notifier.h
new file mode 100644
index 0000000..24ffba3
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Notifier.h
@@ -0,0 +1,154 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <atomic>
+#include <functional>
+#include <thread>
+#include <utility>
+
+#include <hal/Types.h>
+#include <units/units.h>
+#include <wpi/Twine.h>
+#include <wpi/deprecated.h>
+#include <wpi/mutex.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+class Notifier : public ErrorBase {
+ public:
+  /**
+   * Create a Notifier for timer event notification.
+   *
+   * @param handler The handler is called at the notification time which is set
+   *                using StartSingle or StartPeriodic.
+   */
+  explicit Notifier(std::function<void()> handler);
+
+  template <typename Callable, typename Arg, typename... Args>
+  Notifier(Callable&& f, Arg&& arg, Args&&... args)
+      : Notifier(std::bind(std::forward<Callable>(f), std::forward<Arg>(arg),
+                           std::forward<Args>(args)...)) {}
+
+  /**
+   * Free the resources for a timer event.
+   */
+  virtual ~Notifier();
+
+  Notifier(Notifier&& rhs);
+  Notifier& operator=(Notifier&& rhs);
+
+  /**
+   * Sets the name of the notifier.  Used for debugging purposes only.
+   *
+   * @param name Name
+   */
+  void SetName(const wpi::Twine& name);
+
+  /**
+   * Change the handler function.
+   *
+   * @param handler Handler
+   */
+  void SetHandler(std::function<void()> handler);
+
+  /**
+   * Register for single event notification.
+   *
+   * A timer event is queued for a single event after the specified delay.
+   *
+   * @param delay Seconds to wait before the handler is called.
+   */
+  WPI_DEPRECATED("Use unit-safe StartSingle method instead.")
+  void StartSingle(double delay);
+
+  /**
+   * Register for single event notification.
+   *
+   * A timer event is queued for a single event after the specified delay.
+   *
+   * @param delay Amount of time to wait before the handler is called.
+   */
+  void StartSingle(units::second_t delay);
+
+  /**
+   * Register for periodic event notification.
+   *
+   * A timer event is queued for periodic event notification. Each time the
+   * interrupt occurs, the event will be immediately requeued for the same time
+   * interval.
+   *
+   * @param period Period in seconds to call the handler starting one period
+   *               after the call to this method.
+   */
+  WPI_DEPRECATED("Use unit-safe StartPeriodic method instead.")
+  void StartPeriodic(double period);
+
+  /**
+   * Register for periodic event notification.
+   *
+   * A timer event is queued for periodic event notification. Each time the
+   * interrupt occurs, the event will be immediately requeued for the same time
+   * interval.
+   *
+   * @param period Period to call the handler starting one period
+   *               after the call to this method.
+   */
+  void StartPeriodic(units::second_t period);
+
+  /**
+   * Stop timer events from occuring.
+   *
+   * Stop any repeating timer events from occuring. This will also remove any
+   * single notification events from the queue.
+   *
+   * If a timer-based call to the registered handler is in progress, this
+   * function will block until the handler call is complete.
+   */
+  void Stop();
+
+ private:
+  /**
+   * Update the HAL alarm time.
+   *
+   * @param triggerTime the time at which the next alarm will be triggered
+   */
+  void UpdateAlarm(uint64_t triggerTime);
+
+  /**
+   * Update the HAL alarm time based on m_expirationTime.
+   */
+  void UpdateAlarm();
+
+  // The thread waiting on the HAL alarm
+  std::thread m_thread;
+
+  // Held while updating process information
+  wpi::mutex m_processMutex;
+
+  // HAL handle, atomic for proper destruction
+  std::atomic<HAL_NotifierHandle> m_notifier{0};
+
+  // Address of the handler
+  std::function<void()> m_handler;
+
+  // The absolute expiration time
+  double m_expirationTime = 0;
+
+  // The relative time (either periodic or single)
+  double m_period = 0;
+
+  // True if this is a periodic event
+  bool m_periodic = false;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/PIDBase.h b/wpilibc/src/main/native/include/frc/PIDBase.h
new file mode 100644
index 0000000..513d46b
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/PIDBase.h
@@ -0,0 +1,408 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <wpi/deprecated.h>
+#include <wpi/mutex.h>
+
+#include "frc/Base.h"
+#include "frc/LinearFilter.h"
+#include "frc/PIDInterface.h"
+#include "frc/PIDOutput.h"
+#include "frc/PIDSource.h"
+#include "frc/Timer.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+
+/**
+ * Class implements a PID Control Loop.
+ *
+ * Creates a separate thread which reads the given PIDSource and takes care of
+ * the integral calculations, as well as writing the given PIDOutput.
+ *
+ * This feedback controller runs in discrete time, so time deltas are not used
+ * in the integral and derivative calculations. Therefore, the sample rate
+ * affects the controller's behavior for a given set of PID constants.
+ */
+class PIDBase : public PIDInterface,
+                public PIDOutput,
+                public Sendable,
+                public SendableHelper<PIDBase> {
+ public:
+  /**
+   * Allocate a PID object with the given constants for P, I, D.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output value
+   */
+  WPI_DEPRECATED("All APIs which use this have been deprecated.")
+  PIDBase(double p, double i, double d, PIDSource& source, PIDOutput& output);
+
+  /**
+   * Allocate a PID object with the given constants for P, I, D.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output value
+   */
+  WPI_DEPRECATED("All APIs which use this have been deprecated.")
+  PIDBase(double p, double i, double d, double f, PIDSource& source,
+          PIDOutput& output);
+
+  virtual ~PIDBase() = default;
+
+  /**
+   * Return the current PID result.
+   *
+   * This is always centered on zero and constrained the the max and min outs.
+   *
+   * @return the latest calculated output
+   */
+  virtual double Get() const;
+
+  /**
+   * Set the PID controller to consider the input to be continuous,
+   *
+   * Rather then using the max and min input range as constraints, it considers
+   * them to be the same point and automatically calculates the shortest route
+   * to the setpoint.
+   *
+   * @param continuous true turns on continuous, false turns off continuous
+   */
+  virtual void SetContinuous(bool continuous = true);
+
+  /**
+   * Sets the maximum and minimum values expected from the input.
+   *
+   * @param minimumInput the minimum value expected from the input
+   * @param maximumInput the maximum value expected from the output
+   */
+  virtual void SetInputRange(double minimumInput, double maximumInput);
+
+  /**
+   * Sets the minimum and maximum values to write.
+   *
+   * @param minimumOutput the minimum value to write to the output
+   * @param maximumOutput the maximum value to write to the output
+   */
+  virtual void SetOutputRange(double minimumOutput, double maximumOutput);
+
+  /**
+   * Set the PID Controller gain parameters.
+   *
+   * Set the proportional, integral, and differential coefficients.
+   *
+   * @param p Proportional coefficient
+   * @param i Integral coefficient
+   * @param d Differential coefficient
+   */
+  void SetPID(double p, double i, double d) override;
+
+  /**
+   * Set the PID Controller gain parameters.
+   *
+   * Set the proportional, integral, and differential coefficients.
+   *
+   * @param p Proportional coefficient
+   * @param i Integral coefficient
+   * @param d Differential coefficient
+   * @param f Feed forward coefficient
+   */
+  virtual void SetPID(double p, double i, double d, double f);
+
+  /**
+   * Set the Proportional coefficient of the PID controller gain.
+   *
+   * @param p proportional coefficient
+   */
+  void SetP(double p);
+
+  /**
+   * Set the Integral coefficient of the PID controller gain.
+   *
+   * @param i integral coefficient
+   */
+  void SetI(double i);
+
+  /**
+   * Set the Differential coefficient of the PID controller gain.
+   *
+   * @param d differential coefficient
+   */
+  void SetD(double d);
+
+  /**
+   * Get the Feed forward coefficient of the PID controller gain.
+   *
+   * @param f Feed forward coefficient
+   */
+  void SetF(double f);
+
+  /**
+   * Get the Proportional coefficient.
+   *
+   * @return proportional coefficient
+   */
+  double GetP() const override;
+
+  /**
+   * Get the Integral coefficient.
+   *
+   * @return integral coefficient
+   */
+  double GetI() const override;
+
+  /**
+   * Get the Differential coefficient.
+   *
+   * @return differential coefficient
+   */
+  double GetD() const override;
+
+  /**
+   * Get the Feed forward coefficient.
+   *
+   * @return Feed forward coefficient
+   */
+  virtual double GetF() const;
+
+  /**
+   * Set the setpoint for the PIDBase.
+   *
+   * @param setpoint the desired setpoint
+   */
+  void SetSetpoint(double setpoint) override;
+
+  /**
+   * Returns the current setpoint of the PIDBase.
+   *
+   * @return the current setpoint
+   */
+  double GetSetpoint() const override;
+
+  /**
+   * Returns the change in setpoint over time of the PIDBase.
+   *
+   * @return the change in setpoint over time
+   */
+  double GetDeltaSetpoint() const;
+
+  /**
+   * Returns the current difference of the input from the setpoint.
+   *
+   * @return the current error
+   */
+  virtual double GetError() const;
+
+  /**
+   * Returns the current average of the error over the past few iterations.
+   *
+   * You can specify the number of iterations to average with
+   * SetToleranceBuffer() (defaults to 1). This is the same value that is used
+   * for OnTarget().
+   *
+   * @return the average error
+   */
+  WPI_DEPRECATED("Use a LinearFilter as the input and GetError().")
+  virtual double GetAvgError() const;
+
+  /**
+   * Sets what type of input the PID controller will use.
+   */
+  virtual void SetPIDSourceType(PIDSourceType pidSource);
+
+  /**
+   * Returns the type of input the PID controller is using.
+   *
+   * @return the PID controller input type
+   */
+  virtual PIDSourceType GetPIDSourceType() const;
+
+  /**
+   * Set the percentage error which is considered tolerable for use with
+   * OnTarget.
+   *
+   * @param percentage error which is tolerable
+   */
+  WPI_DEPRECATED("Use SetPercentTolerance() instead.")
+  virtual void SetTolerance(double percent);
+
+  /**
+   * Set the absolute error which is considered tolerable for use with
+   * OnTarget.
+   *
+   * @param percentage error which is tolerable
+   */
+  virtual void SetAbsoluteTolerance(double absValue);
+
+  /**
+   * Set the percentage error which is considered tolerable for use with
+   * OnTarget.
+   *
+   * @param percentage error which is tolerable
+   */
+  virtual void SetPercentTolerance(double percentValue);
+
+  /**
+   * Set the number of previous error samples to average for tolerancing. When
+   * determining whether a mechanism is on target, the user may want to use a
+   * rolling average of previous measurements instead of a precise position or
+   * velocity. This is useful for noisy sensors which return a few erroneous
+   * measurements when the mechanism is on target. However, the mechanism will
+   * not register as on target for at least the specified bufLength cycles.
+   *
+   * @param bufLength Number of previous cycles to average. Defaults to 1.
+   */
+  WPI_DEPRECATED("Use a LinearDigitalFilter as the input.")
+  virtual void SetToleranceBuffer(int buf = 1);
+
+  /**
+   * Return true if the error is within the percentage of the total input range,
+   * determined by SetTolerance. This asssumes that the maximum and minimum
+   * input were set using SetInput.
+   *
+   * Currently this just reports on target as the actual value passes through
+   * the setpoint. Ideally it should be based on being within the tolerance for
+   * some period of time.
+   *
+   * This will return false until at least one input value has been computed.
+   */
+  virtual bool OnTarget() const;
+
+  /**
+   * Reset the previous error, the integral term, and disable the controller.
+   */
+  void Reset() override;
+
+  /**
+   * Passes the output directly to SetSetpoint().
+   *
+   * PIDControllers can be nested by passing a PIDController as another
+   * PIDController's output. In that case, the output of the parent controller
+   * becomes the input (i.e., the reference) of the child.
+   *
+   * It is the caller's responsibility to put the data into a valid form for
+   * SetSetpoint().
+   */
+  void PIDWrite(double output) override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ protected:
+  // Is the pid controller enabled
+  bool m_enabled = false;
+
+  mutable wpi::mutex m_thisMutex;
+
+  // Ensures when Disable() is called, PIDWrite() won't run if Calculate()
+  // is already running at that time.
+  mutable wpi::mutex m_pidWriteMutex;
+
+  PIDSource* m_pidInput;
+  PIDOutput* m_pidOutput;
+  Timer m_setpointTimer;
+
+  /**
+   * Read the input, calculate the output accordingly, and write to the output.
+   * This should only be called by the Notifier.
+   */
+  virtual void Calculate();
+
+  /**
+   * Calculate the feed forward term.
+   *
+   * Both of the provided feed forward calculations are velocity feed forwards.
+   * If a different feed forward calculation is desired, the user can override
+   * this function and provide his or her own. This function does no
+   * synchronization because the PIDBase class only calls it in synchronized
+   * code, so be careful if calling it oneself.
+   *
+   * If a velocity PID controller is being used, the F term should be set to 1
+   * over the maximum setpoint for the output. If a position PID controller is
+   * being used, the F term should be set to 1 over the maximum speed for the
+   * output measured in setpoint units per this controller's update period (see
+   * the default period in this class's constructor).
+   */
+  virtual double CalculateFeedForward();
+
+  /**
+   * Wraps error around for continuous inputs. The original error is returned if
+   * continuous mode is disabled. This is an unsynchronized function.
+   *
+   * @param error The current error of the PID controller.
+   * @return Error for continuous inputs.
+   */
+  double GetContinuousError(double error) const;
+
+ private:
+  // Factor for "proportional" control
+  double m_P;
+
+  // Factor for "integral" control
+  double m_I;
+
+  // Factor for "derivative" control
+  double m_D;
+
+  // Factor for "feed forward" control
+  double m_F;
+
+  // |maximum output|
+  double m_maximumOutput = 1.0;
+
+  // |minimum output|
+  double m_minimumOutput = -1.0;
+
+  // Maximum input - limit setpoint to this
+  double m_maximumInput = 0;
+
+  // Minimum input - limit setpoint to this
+  double m_minimumInput = 0;
+
+  // input range - difference between maximum and minimum
+  double m_inputRange = 0;
+
+  // Do the endpoints wrap around? eg. Absolute encoder
+  bool m_continuous = false;
+
+  // The prior error (used to compute velocity)
+  double m_prevError = 0;
+
+  // The sum of the errors for use in the integral calc
+  double m_totalError = 0;
+
+  enum {
+    kAbsoluteTolerance,
+    kPercentTolerance,
+    kNoTolerance
+  } m_toleranceType = kNoTolerance;
+
+  // The percetage or absolute error that is considered on target.
+  double m_tolerance = 0.05;
+
+  double m_setpoint = 0;
+  double m_prevSetpoint = 0;
+  double m_error = 0;
+  double m_result = 0;
+
+  LinearFilter<double> m_filter{{}, {}};
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/PIDController.h b/wpilibc/src/main/native/include/frc/PIDController.h
new file mode 100644
index 0000000..88b0786
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/PIDController.h
@@ -0,0 +1,137 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <wpi/deprecated.h>
+#include <wpi/mutex.h>
+
+#include "frc/Base.h"
+#include "frc/Controller.h"
+#include "frc/Notifier.h"
+#include "frc/PIDBase.h"
+#include "frc/PIDSource.h"
+#include "frc/Timer.h"
+
+namespace frc {
+
+class PIDOutput;
+
+/**
+ * Class implements a PID Control Loop.
+ *
+ * Creates a separate thread which reads the given PIDSource and takes care of
+ * the integral calculations, as well as writing the given PIDOutput.
+ *
+ * This feedback controller runs in discrete time, so time deltas are not used
+ * in the integral and derivative calculations. Therefore, the sample rate
+ * affects the controller's behavior for a given set of PID constants.
+ */
+class PIDController : public PIDBase, public Controller {
+ public:
+  /**
+   * Allocate a PID object with the given constants for P, I, D.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output value
+   * @param period the loop time for doing calculations in seconds. This
+   *               particularly affects calculations of the integral and
+   *               differental terms. The default is 0.05 (50ms).
+   */
+  WPI_DEPRECATED("Use frc2::PIDController class instead.")
+  PIDController(double p, double i, double d, PIDSource* source,
+                PIDOutput* output, double period = 0.05);
+
+  /**
+   * Allocate a PID object with the given constants for P, I, D.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output value
+   * @param period the loop time for doing calculations in seconds. This
+   *               particularly affects calculations of the integral and
+   *               differental terms. The default is 0.05 (50ms).
+   */
+  WPI_DEPRECATED("Use frc2::PIDController class instead.")
+  PIDController(double p, double i, double d, double f, PIDSource* source,
+                PIDOutput* output, double period = 0.05);
+
+  /**
+   * Allocate a PID object with the given constants for P, I, D.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output value
+   * @param period the loop time for doing calculations in seconds. This
+   *               particularly affects calculations of the integral and
+   *               differental terms. The default is 0.05 (50ms).
+   */
+  WPI_DEPRECATED("Use frc2::PIDController class instead.")
+  PIDController(double p, double i, double d, PIDSource& source,
+                PIDOutput& output, double period = 0.05);
+
+  /**
+   * Allocate a PID object with the given constants for P, I, D.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output value
+   * @param period the loop time for doing calculations in seconds. This
+   *               particularly affects calculations of the integral and
+   *               differental terms. The default is 0.05 (50ms).
+   */
+  WPI_DEPRECATED("Use frc2::PIDController class instead.")
+  PIDController(double p, double i, double d, double f, PIDSource& source,
+                PIDOutput& output, double period = 0.05);
+
+  ~PIDController() override;
+
+  /**
+   * Begin running the PIDController.
+   */
+  void Enable() override;
+
+  /**
+   * Stop running the PIDController, this sets the output to zero before
+   * stopping.
+   */
+  void Disable() override;
+
+  /**
+   * Set the enabled state of the PIDController.
+   */
+  void SetEnabled(bool enable);
+
+  /**
+   * Return true if PIDController is enabled.
+   */
+  bool IsEnabled() const;
+
+  /**
+   * Reset the previous error, the integral term, and disable the controller.
+   */
+  void Reset() override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  std::unique_ptr<Notifier> m_controlLoop;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/PIDInterface.h b/wpilibc/src/main/native/include/frc/PIDInterface.h
new file mode 100644
index 0000000..8162aa5
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/PIDInterface.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/deprecated.h>
+
+namespace frc {
+
+class PIDInterface {
+ public:
+  WPI_DEPRECATED("All APIs which use this have been deprecated.")
+  PIDInterface() = default;
+  PIDInterface(PIDInterface&&) = default;
+  PIDInterface& operator=(PIDInterface&&) = default;
+
+  virtual void SetPID(double p, double i, double d) = 0;
+  virtual double GetP() const = 0;
+  virtual double GetI() const = 0;
+  virtual double GetD() const = 0;
+
+  virtual void SetSetpoint(double setpoint) = 0;
+  virtual double GetSetpoint() const = 0;
+
+  virtual void Reset() = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/PIDOutput.h b/wpilibc/src/main/native/include/frc/PIDOutput.h
new file mode 100644
index 0000000..37fb2a1
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/PIDOutput.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/Base.h"
+
+namespace frc {
+
+/**
+ * PIDOutput interface is a generic output for the PID class.
+ *
+ * PWMs use this class. Users implement this interface to allow for a
+ * PIDController to read directly from the inputs.
+ */
+class PIDOutput {
+ public:
+  virtual void PIDWrite(double output) = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/PIDSource.h b/wpilibc/src/main/native/include/frc/PIDSource.h
new file mode 100644
index 0000000..1a807b1
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/PIDSource.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+enum class PIDSourceType { kDisplacement, kRate };
+
+/**
+ * PIDSource interface is a generic sensor source for the PID class.
+ *
+ * All sensors that can be used with the PID class will implement the PIDSource
+ * that returns a standard value that will be used in the PID code.
+ */
+class PIDSource {
+ public:
+  virtual ~PIDSource() = default;
+
+  /**
+   * Set which parameter you are using as a process control variable.
+   *
+   * @param pidSource An enum to select the parameter.
+   */
+  virtual void SetPIDSourceType(PIDSourceType pidSource);
+
+  virtual PIDSourceType GetPIDSourceType() const;
+
+  virtual double PIDGet() = 0;
+
+ protected:
+  PIDSourceType m_pidSource = PIDSourceType::kDisplacement;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/PWM.h b/wpilibc/src/main/native/include/frc/PWM.h
new file mode 100644
index 0000000..406a93e
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/PWM.h
@@ -0,0 +1,241 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <hal/Types.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/MotorSafety.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+class AddressableLED;
+class SendableBuilder;
+
+/**
+ * Class implements the PWM generation in the FPGA.
+ *
+ * The values supplied as arguments for PWM outputs range from -1.0 to 1.0. They
+ * are mapped to the hardware dependent values, in this case 0-2000 for the
+ * FPGA. Changes are immediately sent to the FPGA, and the update occurs at the
+ * next FPGA cycle (5.005ms). There is no delay.
+ *
+ * As of revision 0.1.10 of the FPGA, the FPGA interprets the 0-2000 values as
+ * follows:
+ *   - 2000 = maximum pulse width
+ *   - 1999 to 1001 = linear scaling from "full forward" to "center"
+ *   - 1000 = center value
+ *   - 999 to 2 = linear scaling from "center" to "full reverse"
+ *   - 1 = minimum pulse width (currently 0.5ms)
+ *   - 0 = disabled (i.e. PWM output is held low)
+ */
+class PWM : public MotorSafety, public Sendable, public SendableHelper<PWM> {
+ public:
+  friend class AddressableLED;
+  /**
+   * Represents the amount to multiply the minimum servo-pulse pwm period by.
+   */
+  enum PeriodMultiplier {
+    /**
+     * Don't skip pulses. PWM pulses occur every 5.005 ms
+     */
+    kPeriodMultiplier_1X = 1,
+    /**
+     * Skip every other pulse. PWM pulses occur every 10.010 ms
+     */
+    kPeriodMultiplier_2X = 2,
+    /**
+     * Skip three out of four pulses. PWM pulses occur every 20.020 ms
+     */
+    kPeriodMultiplier_4X = 4
+  };
+
+  /**
+   * Allocate a PWM given a channel number.
+   *
+   * Checks channel value range and allocates the appropriate channel.
+   * The allocation is only done to help users ensure that they don't double
+   * assign channels.
+   *
+   * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the
+   *                MXP port
+   */
+  explicit PWM(int channel);
+
+  /**
+   * Free the PWM channel.
+   *
+   * Free the resource associated with the PWM channel and set the value to 0.
+   */
+  ~PWM() override;
+
+  PWM(PWM&&) = default;
+  PWM& operator=(PWM&&) = default;
+
+  // MotorSafety interface
+  void StopMotor() override;
+  void GetDescription(wpi::raw_ostream& desc) const override;
+
+  /**
+   * Set the PWM value directly to the hardware.
+   *
+   * Write a raw value to a PWM channel.
+   *
+   * @param value Raw PWM value.
+   */
+  virtual void SetRaw(uint16_t value);
+
+  /**
+   * Get the PWM value directly from the hardware.
+   *
+   * Read a raw value from a PWM channel.
+   *
+   * @return Raw PWM control value.
+   */
+  virtual uint16_t GetRaw() const;
+
+  /**
+   * Set the PWM value based on a position.
+   *
+   * This is intended to be used by servos.
+   *
+   * @pre SetMaxPositivePwm() called.
+   * @pre SetMinNegativePwm() called.
+   *
+   * @param pos The position to set the servo between 0.0 and 1.0.
+   */
+  virtual void SetPosition(double pos);
+
+  /**
+   * Get the PWM value in terms of a position.
+   *
+   * This is intended to be used by servos.
+   *
+   * @pre SetMaxPositivePwm() called.
+   * @pre SetMinNegativePwm() called.
+   *
+   * @return The position the servo is set to between 0.0 and 1.0.
+   */
+  virtual double GetPosition() const;
+
+  /**
+   * Set the PWM value based on a speed.
+   *
+   * This is intended to be used by speed controllers.
+   *
+   * @pre SetMaxPositivePwm() called.
+   * @pre SetMinPositivePwm() called.
+   * @pre SetCenterPwm() called.
+   * @pre SetMaxNegativePwm() called.
+   * @pre SetMinNegativePwm() called.
+   *
+   * @param speed The speed to set the speed controller between -1.0 and 1.0.
+   */
+  virtual void SetSpeed(double speed);
+
+  /**
+   * Get the PWM value in terms of speed.
+   *
+   * This is intended to be used by speed controllers.
+   *
+   * @pre SetMaxPositivePwm() called.
+   * @pre SetMinPositivePwm() called.
+   * @pre SetMaxNegativePwm() called.
+   * @pre SetMinNegativePwm() called.
+   *
+   * @return The most recently set speed between -1.0 and 1.0.
+   */
+  virtual double GetSpeed() const;
+
+  /**
+   * Temporarily disables the PWM output. The next set call will reenable
+   * the output.
+   */
+  virtual void SetDisabled();
+
+  /**
+   * Slow down the PWM signal for old devices.
+   *
+   * @param mult The period multiplier to apply to this channel
+   */
+  void SetPeriodMultiplier(PeriodMultiplier mult);
+
+  void SetZeroLatch();
+
+  /**
+   * Optionally eliminate the deadband from a speed controller.
+   *
+   * @param eliminateDeadband If true, set the motor curve on the Jaguar to
+   *                          eliminate the deadband in the middle of the range.
+   *                          Otherwise, keep the full range without modifying
+   *                          any values.
+   */
+  void EnableDeadbandElimination(bool eliminateDeadband);
+
+  /**
+   * Set the bounds on the PWM pulse widths.
+   *
+   * This sets the bounds on the PWM values for a particular type of controller.
+   * The values determine the upper and lower speeds as well as the deadband
+   * bracket.
+   *
+   * @param max         The max PWM pulse width in ms
+   * @param deadbandMax The high end of the deadband range pulse width in ms
+   * @param center      The center (off) pulse width in ms
+   * @param deadbandMin The low end of the deadband pulse width in ms
+   * @param min         The minimum pulse width in ms
+   */
+  void SetBounds(double max, double deadbandMax, double center,
+                 double deadbandMin, double min);
+
+  /**
+   * Set the bounds on the PWM values.
+   *
+   * This sets the bounds on the PWM values for a particular each type of
+   * controller. The values determine the upper and lower speeds as well as the
+   * deadband bracket.
+   *
+   * @param max         The Minimum pwm value
+   * @param deadbandMax The high end of the deadband range
+   * @param center      The center speed (off)
+   * @param deadbandMin The low end of the deadband range
+   * @param min         The minimum pwm value
+   */
+  void SetRawBounds(int max, int deadbandMax, int center, int deadbandMin,
+                    int min);
+
+  /**
+   * Get the bounds on the PWM values.
+   *
+   * This Gets the bounds on the PWM values for a particular each type of
+   * controller. The values determine the upper and lower speeds as well as the
+   * deadband bracket.
+   *
+   * @param max         The Minimum pwm value
+   * @param deadbandMax The high end of the deadband range
+   * @param center      The center speed (off)
+   * @param deadbandMin The low end of the deadband range
+   * @param min         The minimum pwm value
+   */
+  void GetRawBounds(int32_t* max, int32_t* deadbandMax, int32_t* center,
+                    int32_t* deadbandMin, int32_t* min);
+
+  int GetChannel() const;
+
+ protected:
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  int m_channel;
+  hal::Handle<HAL_DigitalHandle> m_handle;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/PWMSparkMax.h b/wpilibc/src/main/native/include/frc/PWMSparkMax.h
new file mode 100644
index 0000000..3ce6466
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/PWMSparkMax.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * REV Robotics SPARK MAX Speed Controller.
+ *
+ * Note that the SPARK MAX uses the following bounds for PWM values. These
+ * values should work reasonably well for most controllers, but if users
+ * experience issues such as asymmetric behavior around the deadband or
+ * inability to saturate the controller in either direction, calibration is
+ * recommended. The calibration procedure can be found in the SPARK MAX User
+ * Manual available from REV Robotics.
+ *
+ * \li 2.003ms = full "forward"
+ * \li 1.550ms = the "high end" of the deadband range
+ * \li 1.500ms = center of the deadband range (off)
+ * \li 1.460ms = the "low end" of the deadband range
+ * \li 0.999ms = full "reverse"
+ */
+class PWMSparkMax : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a SPARK MAX.
+   *
+   * @param channel The PWM channel that the SPARK MAX is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit PWMSparkMax(int channel);
+
+  PWMSparkMax(PWMSparkMax&&) = default;
+  PWMSparkMax& operator=(PWMSparkMax&&) = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/PWMSpeedController.h b/wpilibc/src/main/native/include/frc/PWMSpeedController.h
new file mode 100644
index 0000000..b827d30
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/PWMSpeedController.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWM.h"
+#include "frc/SpeedController.h"
+
+namespace frc {
+
+/**
+ * Common base class for all PWM Speed Controllers.
+ */
+class PWMSpeedController : public PWM, public SpeedController {
+ public:
+  PWMSpeedController(PWMSpeedController&&) = default;
+  PWMSpeedController& operator=(PWMSpeedController&&) = default;
+
+  /**
+   * Set the PWM value.
+   *
+   * The PWM value is set using a range of -1.0 to 1.0, appropriately scaling
+   * the value for the FPGA.
+   *
+   * @param speed The speed value between -1.0 and 1.0 to set.
+   */
+  void Set(double value) override;
+
+  /**
+   * Get the recently set value of the PWM.
+   *
+   * @return The most recently set value for the PWM between -1.0 and 1.0.
+   */
+  double Get() const override;
+
+  void SetInverted(bool isInverted) override;
+
+  bool GetInverted() const override;
+
+  void Disable() override;
+
+  void StopMotor() override;
+
+  /**
+   * Write out the PID value as seen in the PIDOutput base object.
+   *
+   * @param output Write out the PWM value as was found in the PIDController
+   */
+  void PIDWrite(double output) override;
+
+ protected:
+  /**
+   * Constructor for a PWM Speed Controller connected via PWM.
+   *
+   * @param channel The PWM channel that the controller is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit PWMSpeedController(int channel);
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  bool m_isInverted = false;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/PWMTalonFX.h b/wpilibc/src/main/native/include/frc/PWMTalonFX.h
new file mode 100644
index 0000000..d85c7ca
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/PWMTalonFX.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Cross the Road Electronics (CTRE) Talon FX Speed Controller with PWM
+ * control.
+ *
+ * Note that the Talon FX uses the following bounds for PWM values. These
+ * values should work reasonably well for most controllers, but if users
+ * experience issues such as asymmetric behavior around the deadband or
+ * inability to saturate the controller in either direction, calibration is
+ * recommended. The calibration procedure can be found in the Talon FX User
+ * Manual available from Cross The Road Electronics.
+ *
+ * \li 2.004ms = full "forward"
+ * \li 1.520ms = the "high end" of the deadband range
+ * \li 1.500ms = center of the deadband range (off)
+ * \li 1.480ms = the "low end" of the deadband range
+ * \li 0.997ms = full "reverse"
+ */
+class PWMTalonFX : public PWMSpeedController {
+ public:
+  /**
+   * Construct a Talon FX connected via PWM.
+   *
+   * @param channel The PWM channel that the Talon FX is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit PWMTalonFX(int channel);
+
+  PWMTalonFX(PWMTalonFX&&) = default;
+  PWMTalonFX& operator=(PWMTalonFX&&) = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/PWMTalonSRX.h b/wpilibc/src/main/native/include/frc/PWMTalonSRX.h
new file mode 100644
index 0000000..b9c8369
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/PWMTalonSRX.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Cross the Road Electronics (CTRE) Talon SRX Speed Controller with PWM
+ * control.
+ *
+ * Note that the Talon SRX uses the following bounds for PWM values. These
+ * values should work reasonably well for most controllers, but if users
+ * experience issues such as asymmetric behavior around the deadband or
+ * inability to saturate the controller in either direction, calibration is
+ * recommended. The calibration procedure can be found in the Talon SRX User
+ * Manual available from Cross The Road Electronics.
+ *
+ * \li 2.004ms = full "forward"
+ * \li 1.520ms = the "high end" of the deadband range
+ * \li 1.500ms = center of the deadband range (off)
+ * \li 1.480ms = the "low end" of the deadband range
+ * \li 0.997ms = full "reverse"
+ */
+class PWMTalonSRX : public PWMSpeedController {
+ public:
+  /**
+   * Construct a Talon SRX connected via PWM.
+   *
+   * @param channel The PWM channel that the Talon SRX is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit PWMTalonSRX(int channel);
+
+  PWMTalonSRX(PWMTalonSRX&&) = default;
+  PWMTalonSRX& operator=(PWMTalonSRX&&) = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/PWMVenom.h b/wpilibc/src/main/native/include/frc/PWMVenom.h
new file mode 100644
index 0000000..189db43
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/PWMVenom.h
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Playing with Fusion Venom Smart Motor with PWM control.
+ *
+ * Note that the Venom uses the following bounds for PWM values. These
+ * values should work reasonably well for most controllers, but if users
+ * experience issues such as asymmetric behavior around the deadband or
+ * inability to saturate the controller in either direction, calibration is
+ * recommended.
+ *
+ * \li 2.004ms = full "forward"
+ * \li 1.520ms = the "high end" of the deadband range
+ * \li 1.500ms = center of the deadband range (off)
+ * \li 1.480ms = the "low end" of the deadband range
+ * \li 0.997ms = full "reverse"
+ */
+class PWMVenom : public PWMSpeedController {
+ public:
+  /**
+   * Construct a Venom connected via PWM.
+   *
+   * @param channel The PWM channel that the Venom is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit PWMVenom(int channel);
+
+  PWMVenom(PWMVenom&&) = default;
+  PWMVenom& operator=(PWMVenom&&) = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/PWMVictorSPX.h b/wpilibc/src/main/native/include/frc/PWMVictorSPX.h
new file mode 100644
index 0000000..a19e704
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/PWMVictorSPX.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Cross the Road Electronics (CTRE) Victor SPX Speed Controller with PWM
+ * control.
+ *
+ * Note that the Victor SPX uses the following bounds for PWM values. These
+ * values should work reasonably well for most controllers, but if users
+ * experience issues such as asymmetric behavior around the deadband or
+ * inability to saturate the controller in either direction, calibration is
+ * recommended. The calibration procedure can be found in the Victor SPX User
+ * Manual available from Cross The Road Electronics.
+ *
+ * \li 2.004ms = full "forward"
+ * \li 1.520ms = the "high end" of the deadband range
+ * \li 1.500ms = center of the deadband range (off)
+ * \li 1.480ms = the "low end" of the deadband range
+ * \li 0.997ms = full "reverse"
+ */
+class PWMVictorSPX : public PWMSpeedController {
+ public:
+  /**
+   * Construct a Victor SPX connected via PWM.
+   *
+   * @param channel The PWM channel that the Victor SPX is attached to. 0-9
+   *                are on-board, 10-19 are on the MXP port
+   */
+  explicit PWMVictorSPX(int channel);
+
+  PWMVictorSPX(PWMVictorSPX&&) = default;
+  PWMVictorSPX& operator=(PWMVictorSPX&&) = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/PowerDistributionPanel.h b/wpilibc/src/main/native/include/frc/PowerDistributionPanel.h
new file mode 100644
index 0000000..433874b
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/PowerDistributionPanel.h
@@ -0,0 +1,94 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+
+/**
+ * Class for getting voltage, current, temperature, power and energy from the
+ * CAN PDP.
+ */
+class PowerDistributionPanel : public ErrorBase,
+                               public Sendable,
+                               public SendableHelper<PowerDistributionPanel> {
+ public:
+  PowerDistributionPanel();
+  explicit PowerDistributionPanel(int module);
+
+  PowerDistributionPanel(PowerDistributionPanel&&) = default;
+  PowerDistributionPanel& operator=(PowerDistributionPanel&&) = default;
+
+  /**
+   * Query the input voltage of the PDP.
+   *
+   * @return The voltage of the PDP in volts
+   */
+  double GetVoltage() const;
+
+  /**
+   * Query the temperature of the PDP.
+   *
+   * @return The temperature of the PDP in degrees Celsius
+   */
+  double GetTemperature() const;
+
+  /**
+   * Query the current of a single channel of the PDP.
+   *
+   * @return The current of one of the PDP channels (channels 0-15) in Amperes
+   */
+  double GetCurrent(int channel) const;
+
+  /**
+   * Query the total current of all monitored PDP channels (0-15).
+   *
+   * @return The the total current drawn from the PDP channels in Amperes
+   */
+  double GetTotalCurrent() const;
+
+  /**
+   * Query the total power drawn from the monitored PDP channels.
+   *
+   * @return The the total power drawn from the PDP channels in Watts
+   */
+  double GetTotalPower() const;
+
+  /**
+   * Query the total energy drawn from the monitored PDP channels.
+   *
+   * @return The the total energy drawn from the PDP channels in Joules
+   */
+  double GetTotalEnergy() const;
+
+  /**
+   * Reset the total energy drawn from the PDP.
+   *
+   * @see PowerDistributionPanel#GetTotalEnergy
+   */
+  void ResetTotalEnergy();
+
+  /**
+   * Remove all of the fault flags on the PDP.
+   */
+  void ClearStickyFaults();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  hal::Handle<HAL_PDPHandle> m_handle;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Preferences.h b/wpilibc/src/main/native/include/frc/Preferences.h
new file mode 100644
index 0000000..57678a8
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Preferences.h
@@ -0,0 +1,206 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <networktables/NetworkTable.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+/**
+ * The preferences class provides a relatively simple way to save important
+ * values to the roboRIO to access the next time the roboRIO is booted.
+ *
+ * This class loads and saves from a file inside the roboRIO.  The user cannot
+ * access the file directly, but may modify values at specific fields which will
+ * then be automatically periodically saved to the file by the NetworkTable
+ * server.
+ *
+ * This class is thread safe.
+ *
+ * This will also interact with {@link NetworkTable} by creating a table called
+ * "Preferences" with all the key-value pairs.
+ */
+class Preferences : public ErrorBase {
+ public:
+  /**
+   * Get the one and only {@link Preferences} object.
+   *
+   * @return pointer to the {@link Preferences}
+   */
+  static Preferences* GetInstance();
+
+  /**
+   * Returns a vector of all the keys.
+   *
+   * @return a vector of the keys
+   */
+  std::vector<std::string> GetKeys();
+
+  /**
+   * Returns the string at the given key.  If this table does not have a value
+   * for that position, then the given defaultValue will be returned.
+   *
+   * @param key          the key
+   * @param defaultValue the value to return if none exists in the table
+   * @return either the value in the table, or the defaultValue
+   */
+  std::string GetString(wpi::StringRef key, wpi::StringRef defaultValue = "");
+
+  /**
+   * Returns the int at the given key.  If this table does not have a value for
+   * that position, then the given defaultValue value will be returned.
+   *
+   * @param key          the key
+   * @param defaultValue the value to return if none exists in the table
+   * @return either the value in the table, or the defaultValue
+   */
+  int GetInt(wpi::StringRef key, int defaultValue = 0);
+
+  /**
+   * Returns the double at the given key.  If this table does not have a value
+   * for that position, then the given defaultValue value will be returned.
+   *
+   * @param key          the key
+   * @param defaultValue the value to return if none exists in the table
+   * @return either the value in the table, or the defaultValue
+   */
+  double GetDouble(wpi::StringRef key, double defaultValue = 0.0);
+
+  /**
+   * Returns the float at the given key.  If this table does not have a value
+   * for that position, then the given defaultValue value will be returned.
+   *
+   * @param key          the key
+   * @param defaultValue the value to return if none exists in the table
+   * @return either the value in the table, or the defaultValue
+   */
+  float GetFloat(wpi::StringRef key, float defaultValue = 0.0);
+
+  /**
+   * Returns the boolean at the given key.  If this table does not have a value
+   * for that position, then the given defaultValue value will be returned.
+   *
+   * @param key          the key
+   * @param defaultValue the value to return if none exists in the table
+   * @return either the value in the table, or the defaultValue
+   */
+  bool GetBoolean(wpi::StringRef key, bool defaultValue = false);
+
+  /**
+   * Returns the long (int64_t) at the given key.  If this table does not have a
+   * value for that position, then the given defaultValue value will be
+   * returned.
+   *
+   * @param key          the key
+   * @param defaultValue the value to return if none exists in the table
+   * @return either the value in the table, or the defaultValue
+   */
+  int64_t GetLong(wpi::StringRef key, int64_t defaultValue = 0);
+
+  /**
+   * Puts the given string into the preferences table.
+   *
+   * The value may not have quotation marks, nor may the key have any whitespace
+   * nor an equals sign.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  void PutString(wpi::StringRef key, wpi::StringRef value);
+
+  /**
+   * Puts the given int into the preferences table.
+   *
+   * The key may not have any whitespace nor an equals sign.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  void PutInt(wpi::StringRef key, int value);
+
+  /**
+   * Puts the given double into the preferences table.
+   *
+   * The key may not have any whitespace nor an equals sign.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  void PutDouble(wpi::StringRef key, double value);
+
+  /**
+   * Puts the given float into the preferences table.
+   *
+   * The key may not have any whitespace nor an equals sign.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  void PutFloat(wpi::StringRef key, float value);
+
+  /**
+   * Puts the given boolean into the preferences table.
+   *
+   * The key may not have any whitespace nor an equals sign.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  void PutBoolean(wpi::StringRef key, bool value);
+
+  /**
+   * Puts the given long (int64_t) into the preferences table.
+   *
+   * The key may not have any whitespace nor an equals sign.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  void PutLong(wpi::StringRef key, int64_t value);
+
+  /**
+   * Returns whether or not there is a key with the given name.
+   *
+   * @param key the key
+   * @return if there is a value at the given key
+   */
+  bool ContainsKey(wpi::StringRef key);
+
+  /**
+   * Remove a preference.
+   *
+   * @param key the key
+   */
+  void Remove(wpi::StringRef key);
+
+  /**
+   * Remove all preferences.
+   */
+  void RemoveAll();
+
+ protected:
+  Preferences();
+  virtual ~Preferences() = default;
+
+  Preferences(Preferences&&) = default;
+  Preferences& operator=(Preferences&&) = default;
+
+ private:
+  std::shared_ptr<nt::NetworkTable> m_table;
+  NT_EntryListener m_listener;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Relay.h b/wpilibc/src/main/native/include/frc/Relay.h
new file mode 100644
index 0000000..c903fc0
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Relay.h
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <hal/Types.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/MotorSafety.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+
+/**
+ * Class for Spike style relay outputs.
+ *
+ * Relays are intended to be connected to spikes or similar relays. The relay
+ * channels controls a pair of pins that are either both off, one on, the other
+ * on, or both on. This translates into two spike outputs at 0v, one at 12v and
+ * one at 0v, one at 0v and the other at 12v, or two spike outputs at 12V. This
+ * allows off, full forward, or full reverse control of motors without variable
+ * speed. It also allows the two channels (forward and reverse) to be used
+ * independently for something that does not care about voltage polarity (like
+ * a solenoid).
+ */
+class Relay : public MotorSafety,
+              public Sendable,
+              public SendableHelper<Relay> {
+ public:
+  enum Value { kOff, kOn, kForward, kReverse };
+  enum Direction { kBothDirections, kForwardOnly, kReverseOnly };
+
+  /**
+   * Relay constructor given a channel.
+   *
+   * This code initializes the relay and reserves all resources that need to be
+   * locked. Initially the relay is set to both lines at 0v.
+   *
+   * @param channel   The channel number (0-3).
+   * @param direction The direction that the Relay object will control.
+   */
+  explicit Relay(int channel, Direction direction = kBothDirections);
+
+  /**
+   * Free the resource associated with a relay.
+   *
+   * The relay channels are set to free and the relay output is turned off.
+   */
+  ~Relay() override;
+
+  Relay(Relay&&) = default;
+  Relay& operator=(Relay&&) = default;
+
+  /**
+   * Set the relay state.
+   *
+   * Valid values depend on which directions of the relay are controlled by the
+   * object.
+   *
+   * When set to kBothDirections, the relay can be any of the four states:
+   * 0v-0v, 0v-12v, 12v-0v, 12v-12v
+   *
+   * When set to kForwardOnly or kReverseOnly, you can specify the constant for
+   * the direction or you can simply specify kOff and kOn.  Using only kOff and
+   * kOn is recommended.
+   *
+   * @param value The state to set the relay.
+   */
+  void Set(Value value);
+
+  /**
+   * Get the Relay State
+   *
+   * Gets the current state of the relay.
+   *
+   * When set to kForwardOnly or kReverseOnly, value is returned as kOn/kOff not
+   * kForward/kReverse (per the recommendation in Set).
+   *
+   * @return The current state of the relay as a Relay::Value
+   */
+  Value Get() const;
+
+  int GetChannel() const;
+
+  // MotorSafety interface
+  void StopMotor() override;
+
+  void GetDescription(wpi::raw_ostream& desc) const override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  int m_channel;
+  Direction m_direction;
+
+  hal::Handle<HAL_RelayHandle> m_forwardHandle;
+  hal::Handle<HAL_RelayHandle> m_reverseHandle;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Resource.h b/wpilibc/src/main/native/include/frc/Resource.h
new file mode 100644
index 0000000..e9759d5
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Resource.h
@@ -0,0 +1,92 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <wpi/mutex.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+/**
+ * The Resource class is a convenient way to track allocated resources.
+ *
+ * It tracks them as indicies in the range [0 .. elements - 1]. E.g. the library
+ * uses this to track hardware channel allocation.
+ *
+ * The Resource class does not allocate the hardware channels or other
+ * resources; it just tracks which indices were marked in use by Allocate and
+ * not yet freed by Free.
+ */
+class Resource : public ErrorBase {
+ public:
+  virtual ~Resource() = default;
+
+  /**
+   * Factory method to create a Resource allocation-tracker *if* needed.
+   *
+   * @param r        address of the caller's Resource pointer. If *r == nullptr,
+   *                 this will construct a Resource and make *r point to it. If
+   *                 *r != nullptr, i.e. the caller already has a Resource
+   *                 instance, this won't do anything.
+   * @param elements the number of elements for this Resource allocator to
+   *                 track, that is, it will allocate resource numbers in the
+   *                 range [0 .. elements - 1].
+   */
+  static void CreateResourceObject(std::unique_ptr<Resource>& r,
+                                   uint32_t elements);
+
+  /**
+   * Allocate storage for a new instance of Resource.
+   *
+   * Allocate a bool array of values that will get initialized to indicate that
+   * no resources have been allocated yet. The indicies of the resources are
+   * [0 .. elements - 1].
+   */
+  explicit Resource(uint32_t size);
+
+  /**
+   * Allocate a resource.
+   *
+   * When a resource is requested, mark it allocated. In this case, a free
+   * resource value within the range is located and returned after it is marked
+   * allocated.
+   */
+  uint32_t Allocate(const std::string& resourceDesc);
+
+  /**
+   * Allocate a specific resource value.
+   *
+   * The user requests a specific resource value, i.e. channel number and it is
+   * verified unallocated, then returned.
+   */
+  uint32_t Allocate(uint32_t index, const std::string& resourceDesc);
+
+  /**
+   * Free an allocated resource.
+   *
+   * After a resource is no longer needed, for example a destructor is called
+   * for a channel assignment class, Free will release the resource value so it
+   * can be reused somewhere else in the program.
+   */
+  void Free(uint32_t index);
+
+ private:
+  std::vector<bool> m_isAllocated;
+  wpi::mutex m_allocateMutex;
+
+  static wpi::mutex m_createMutex;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/RobotBase.h b/wpilibc/src/main/native/include/frc/RobotBase.h
new file mode 100644
index 0000000..725aa97
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/RobotBase.h
@@ -0,0 +1,205 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <chrono>
+#include <thread>
+
+#include <hal/Main.h>
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/Base.h"
+
+namespace frc {
+
+class DriverStation;
+
+int RunHALInitialization();
+
+namespace impl {
+
+template <class Robot>
+void RunRobot(wpi::mutex& m, Robot** robot) {
+  static Robot theRobot;
+  {
+    std::scoped_lock lock{m};
+    *robot = &theRobot;
+  }
+  theRobot.StartCompetition();
+}
+
+}  // namespace impl
+
+template <class Robot>
+int StartRobot() {
+  int halInit = RunHALInitialization();
+  if (halInit != 0) {
+    return halInit;
+  }
+
+  static wpi::mutex m;
+  static wpi::condition_variable cv;
+  static Robot* robot = nullptr;
+  static bool exited = false;
+
+  if (HAL_HasMain()) {
+    std::thread thr([] {
+      try {
+        impl::RunRobot<Robot>(m, &robot);
+      } catch (...) {
+        HAL_ExitMain();
+        {
+          std::scoped_lock lock{m};
+          robot = nullptr;
+          exited = true;
+        }
+        cv.notify_all();
+        throw;
+      }
+
+      HAL_ExitMain();
+      {
+        std::scoped_lock lock{m};
+        robot = nullptr;
+        exited = true;
+      }
+      cv.notify_all();
+    });
+
+    HAL_RunMain();
+
+    // signal loop to exit
+    if (robot) robot->EndCompetition();
+
+    // prefer to join, but detach to exit if it doesn't exit in a timely manner
+    using namespace std::chrono_literals;
+    std::unique_lock lock{m};
+    if (cv.wait_for(lock, 1s, [] { return exited; }))
+      thr.join();
+    else
+      thr.detach();
+  } else {
+    impl::RunRobot<Robot>(m, &robot);
+  }
+
+  return 0;
+}
+
+#define START_ROBOT_CLASS(_ClassName_)                                 \
+  WPI_DEPRECATED("Call frc::StartRobot<" #_ClassName_                  \
+                 ">() in your own main() instead of using the "        \
+                 "START_ROBOT_CLASS(" #_ClassName_ ") macro.")         \
+  int StartRobotClassImpl() { return frc::StartRobot<_ClassName_>(); } \
+  int main() { return StartRobotClassImpl(); }
+
+/**
+ * Implement a Robot Program framework.
+ *
+ * The RobotBase class is intended to be subclassed by a user creating a robot
+ * program. Overridden Autonomous() and OperatorControl() methods are called at
+ * the appropriate time as the match proceeds. In the current implementation,
+ * the Autonomous code will run to completion before the OperatorControl code
+ * could start. In the future the Autonomous code might be spawned as a task,
+ * then killed at the end of the Autonomous period.
+ */
+class RobotBase {
+ public:
+  /**
+   * Determine if the Robot is currently enabled.
+   *
+   * @return True if the Robot is currently enabled by the field controls.
+   */
+  bool IsEnabled() const;
+
+  /**
+   * Determine if the Robot is currently disabled.
+   *
+   * @return True if the Robot is currently disabled by the field controls.
+   */
+  bool IsDisabled() const;
+
+  /**
+   * Determine if the robot is currently in Autonomous mode.
+   *
+   * @return True if the robot is currently operating Autonomously as determined
+   *         by the field controls.
+   */
+  bool IsAutonomous() const;
+
+  /**
+   * Determine if the robot is currently in Operator Control mode.
+   *
+   * @return True if the robot is currently operating in Tele-Op mode as
+   *         determined by the field controls.
+   */
+  bool IsOperatorControl() const;
+
+  /**
+   * Determine if the robot is currently in Test mode.
+   *
+   * @return True if the robot is currently running tests as determined by the
+   *         field controls.
+   */
+  bool IsTest() const;
+
+  /**
+   * Indicates if new data is available from the driver station.
+   *
+   * @return Has new data arrived over the network since the last time this
+   *         function was called?
+   */
+  bool IsNewDataAvailable() const;
+
+  /**
+   * Gets the ID of the main robot thread.
+   */
+  static std::thread::id GetThreadId();
+
+  virtual void StartCompetition() = 0;
+
+  virtual void EndCompetition() = 0;
+
+  static constexpr bool IsReal() {
+#ifdef __FRC_ROBORIO__
+    return true;
+#else
+    return false;
+#endif
+  }
+
+  static constexpr bool IsSimulation() { return !IsReal(); }
+
+ protected:
+  /**
+   * Constructor for a generic robot program.
+   *
+   * User code should be placed in the constructor that runs before the
+   * Autonomous or Operator Control period starts. The constructor will run to
+   * completion before Autonomous is entered.
+   *
+   * This must be used to ensure that the communications code starts. In the
+   * future it would be nice to put this code into it's own task that loads on
+   * boot so ensure that it runs.
+   */
+  RobotBase();
+
+  virtual ~RobotBase();
+
+  // m_ds isn't moved in these because DriverStation is a singleton; every
+  // instance of RobotBase has a reference to the same object.
+  RobotBase(RobotBase&&) noexcept;
+  RobotBase& operator=(RobotBase&&) noexcept;
+
+  DriverStation& m_ds;
+
+  static std::thread::id m_threadId;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/RobotController.h b/wpilibc/src/main/native/include/frc/RobotController.h
new file mode 100644
index 0000000..fae136b
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/RobotController.h
@@ -0,0 +1,188 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+namespace frc {
+
+struct CANStatus {
+  float percentBusUtilization;
+  int busOffCount;
+  int txFullCount;
+  int receiveErrorCount;
+  int transmitErrorCount;
+};
+
+class RobotController {
+ public:
+  RobotController() = delete;
+
+  /**
+   * Return the FPGA Version number.
+   *
+   * For now, expect this to be competition year.
+   *
+   * @return FPGA Version number.
+   */
+  static int GetFPGAVersion();
+
+  /**
+   * Return the FPGA Revision number.
+   *
+   * The format of the revision is 3 numbers. The 12 most significant bits are
+   * the Major Revision. The next 8 bits are the Minor Revision. The 12 least
+   * significant bits are the Build Number.
+   *
+   * @return FPGA Revision number.
+   */
+  static int64_t GetFPGARevision();
+
+  /**
+   * Read the microsecond-resolution timer on the FPGA.
+   *
+   * @return The current time in microseconds according to the FPGA (since FPGA
+   *         reset).
+   */
+  static uint64_t GetFPGATime();
+
+  /**
+   * Get the state of the "USER" button on the roboRIO.
+   *
+   * @return True if the button is currently pressed down
+   */
+  static bool GetUserButton();
+
+  /**
+   * Check if the FPGA outputs are enabled.
+   *
+   * The outputs may be disabled if the robot is disabled or e-stopped, the
+   * watchdog has expired, or if the roboRIO browns out.
+   *
+   * @return True if the FPGA outputs are enabled.
+   */
+  static bool IsSysActive();
+
+  /**
+   * Check if the system is browned out.
+   *
+   * @return True if the system is browned out
+   */
+  static bool IsBrownedOut();
+
+  /**
+   * Get the input voltage to the robot controller.
+   *
+   * @return The controller input voltage value in Volts
+   */
+  static double GetInputVoltage();
+
+  /**
+   * Get the input current to the robot controller.
+   *
+   * @return The controller input current value in Amps
+   */
+  static double GetInputCurrent();
+
+  /**
+   * Get the voltage of the 3.3V rail.
+   *
+   * @return The controller 3.3V rail voltage value in Volts
+   */
+  static double GetVoltage3V3();
+
+  /**
+   * Get the current output of the 3.3V rail.
+   *
+   * @return The controller 3.3V rail output current value in Amps
+   */
+  static double GetCurrent3V3();
+
+  /**
+   * Get the enabled state of the 3.3V rail. The rail may be disabled due to a
+   * controller brownout, a short circuit on the rail, or controller
+   * over-voltage.
+   *
+   * @return The controller 3.3V rail enabled value. True for enabled.
+   */
+  static bool GetEnabled3V3();
+
+  /**
+   * Get the count of the total current faults on the 3.3V rail since the
+   * controller has booted.
+   *
+   * @return The number of faults
+   */
+  static int GetFaultCount3V3();
+
+  /**
+   * Get the voltage of the 5V rail.
+   *
+   * @return The controller 5V rail voltage value in Volts
+   */
+  static double GetVoltage5V();
+
+  /**
+   * Get the current output of the 5V rail.
+   *
+   * @return The controller 5V rail output current value in Amps
+   */
+  static double GetCurrent5V();
+
+  /**
+   * Get the enabled state of the 5V rail. The rail may be disabled due to a
+   * controller brownout, a short circuit on the rail, or controller
+   * over-voltage.
+   *
+   * @return The controller 5V rail enabled value. True for enabled.
+   */
+  static bool GetEnabled5V();
+
+  /**
+   * Get the count of the total current faults on the 5V rail since the
+   * controller has booted.
+   *
+   * @return The number of faults
+   */
+  static int GetFaultCount5V();
+
+  /**
+   * Get the voltage of the 6V rail.
+   *
+   * @return The controller 6V rail voltage value in Volts
+   */
+  static double GetVoltage6V();
+
+  /**
+   * Get the current output of the 6V rail.
+   *
+   * @return The controller 6V rail output current value in Amps
+   */
+  static double GetCurrent6V();
+
+  /**
+   * Get the enabled state of the 6V rail. The rail may be disabled due to a
+   * controller brownout, a short circuit on the rail, or controller
+   * over-voltage.
+   *
+   * @return The controller 6V rail enabled value. True for enabled.
+   */
+  static bool GetEnabled6V();
+
+  /**
+   * Get the count of the total current faults on the 6V rail since the
+   * controller has booted.
+   *
+   * @return The number of faults.
+   */
+  static int GetFaultCount6V();
+
+  static CANStatus GetCANStatus();
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/RobotDrive.h b/wpilibc/src/main/native/include/frc/RobotDrive.h
new file mode 100644
index 0000000..3580003
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/RobotDrive.h
@@ -0,0 +1,453 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/deprecated.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/MotorSafety.h"
+
+namespace frc {
+
+class SpeedController;
+class GenericHID;
+
+/**
+ * Utility class for handling Robot drive based on a definition of the motor
+ * configuration.
+ *
+ * The robot drive class handles basic driving for a robot. Currently, 2 and 4
+ * motor tank and mecanum drive trains are supported. In the future other drive
+ * types like swerve might be implemented. Motor channel numbers are passed
+ * supplied on creation of the class. Those are used for either the Drive
+ * function (intended for hand created drive code, such as autonomous) or with
+ * the Tank/Arcade functions intended to be used for Operator Control driving.
+ */
+class RobotDrive : public MotorSafety {
+ public:
+  enum MotorType {
+    kFrontLeftMotor = 0,
+    kFrontRightMotor = 1,
+    kRearLeftMotor = 2,
+    kRearRightMotor = 3
+  };
+
+  /**
+   * Constructor for RobotDrive with 2 motors specified with channel numbers.
+   *
+   * Set up parameters for a two wheel drive system where the
+   * left and right motor pwm channels are specified in the call.
+   * This call assumes Talons for controlling the motors.
+   *
+   * @param leftMotorChannel  The PWM channel number that drives the left motor.
+   *                          0-9 are on-board, 10-19 are on the MXP port
+   * @param rightMotorChannel The PWM channel number that drives the right
+   *                          motor. 0-9 are on-board, 10-19 are on the MXP port
+   */
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(int leftMotorChannel, int rightMotorChannel);
+
+  /**
+   * Constructor for RobotDrive with 4 motors specified with channel numbers.
+   *
+   * Set up parameters for a four wheel drive system where all four motor
+   * pwm channels are specified in the call.
+   * This call assumes Talons for controlling the motors.
+   *
+   * @param frontLeftMotor  Front left motor channel number. 0-9 are on-board,
+   *                        10-19 are on the MXP port
+   * @param rearLeftMotor   Rear Left motor channel number. 0-9 are on-board,
+   *                        10-19 are on the MXP port
+   * @param frontRightMotor Front right motor channel number. 0-9 are on-board,
+   *                        10-19 are on the MXP port
+   * @param rearRightMotor  Rear Right motor channel number. 0-9 are on-board,
+   *                        10-19 are on the MXP port
+   */
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(int frontLeftMotorChannel, int rearLeftMotorChannel,
+             int frontRightMotorChannel, int rearRightMotorChannel);
+
+  /**
+   * Constructor for RobotDrive with 2 motors specified as SpeedController
+   * objects.
+   *
+   * The SpeedController version of the constructor enables programs to use the
+   * RobotDrive classes with subclasses of the SpeedController objects, for
+   * example, versions with ramping or reshaping of the curve to suit motor bias
+   * or deadband elimination.
+   *
+   * @param leftMotor  The left SpeedController object used to drive the robot.
+   * @param rightMotor The right SpeedController object used to drive the robot.
+   */
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(SpeedController* leftMotor, SpeedController* rightMotor);
+
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(SpeedController& leftMotor, SpeedController& rightMotor);
+
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(std::shared_ptr<SpeedController> leftMotor,
+             std::shared_ptr<SpeedController> rightMotor);
+
+  /**
+   * Constructor for RobotDrive with 4 motors specified as SpeedController
+   * objects.
+   *
+   * Speed controller input version of RobotDrive (see previous comments).
+   *
+   * @param frontLeftMotor  The front left SpeedController object used to drive
+   *                        the robot.
+   * @param rearLeftMotor   The back left SpeedController object used to drive
+   *                        the robot.
+   * @param frontRightMotor The front right SpeedController object used to drive
+   *                        the robot.
+   * @param rearRightMotor  The back right SpeedController object used to drive
+   *                        the robot.
+   */
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(SpeedController* frontLeftMotor, SpeedController* rearLeftMotor,
+             SpeedController* frontRightMotor, SpeedController* rearRightMotor);
+
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(SpeedController& frontLeftMotor, SpeedController& rearLeftMotor,
+             SpeedController& frontRightMotor, SpeedController& rearRightMotor);
+
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(std::shared_ptr<SpeedController> frontLeftMotor,
+             std::shared_ptr<SpeedController> rearLeftMotor,
+             std::shared_ptr<SpeedController> frontRightMotor,
+             std::shared_ptr<SpeedController> rearRightMotor);
+
+  virtual ~RobotDrive() = default;
+
+  RobotDrive(RobotDrive&&) = default;
+  RobotDrive& operator=(RobotDrive&&) = default;
+
+  /**
+   * Drive the motors at "outputMagnitude" and "curve".
+   *
+   * Both outputMagnitude and curve are -1.0 to +1.0 values, where 0.0
+   * represents stopped and not turning. curve < 0 will turn left and curve > 0
+   * will turn right.
+   *
+   * The algorithm for steering provides a constant turn radius for any normal
+   * speed range, both forward and backward. Increasing m_sensitivity causes
+   * sharper turns for fixed values of curve.
+   *
+   * This function will most likely be used in an autonomous routine.
+   *
+   * @param outputMagnitude The speed setting for the outside wheel in a turn,
+   *                        forward or backwards, +1 to -1.
+   * @param curve           The rate of turn, constant for different forward
+   *                        speeds. Set curve < 0 for left turn or curve > 0 for
+   *                        right turn.
+   *
+   * Set curve = e^(-r/w) to get a turn radius r for wheelbase w of your robot.
+   * Conversely, turn radius r = -ln(curve)*w for a given value of curve and
+   * wheelbase w.
+   */
+  void Drive(double outputMagnitude, double curve);
+
+  /**
+   * Provide tank steering using the stored robot configuration.
+   *
+   * Drive the robot using two joystick inputs. The Y-axis will be selected from
+   * each Joystick object.
+   *
+   * @param leftStick  The joystick to control the left side of the robot.
+   * @param rightStick The joystick to control the right side of the robot.
+   * @param squaredInputs If true, the sensitivity will be decreased for small
+   *                      values
+   */
+  void TankDrive(GenericHID* leftStick, GenericHID* rightStick,
+                 bool squaredInputs = true);
+
+  /**
+   * Provide tank steering using the stored robot configuration.
+   *
+   * Drive the robot using two joystick inputs. The Y-axis will be selected from
+   * each Joystick object.
+   *
+   * @param leftStick  The joystick to control the left side of the robot.
+   * @param rightStick The joystick to control the right side of the robot.
+   * @param squaredInputs If true, the sensitivity will be decreased for small
+   *                      values
+   */
+  void TankDrive(GenericHID& leftStick, GenericHID& rightStick,
+                 bool squaredInputs = true);
+
+  /**
+   * Provide tank steering using the stored robot configuration.
+   *
+   * This function lets you pick the axis to be used on each Joystick object for
+   * the left and right sides of the robot.
+   *
+   * @param leftStick  The Joystick object to use for the left side of the
+   *                   robot.
+   * @param leftAxis   The axis to select on the left side Joystick object.
+   * @param rightStick The Joystick object to use for the right side of the
+   *                   robot.
+   * @param rightAxis  The axis to select on the right side Joystick object.
+   * @param squaredInputs If true, the sensitivity will be decreased for small
+   *                      values
+   */
+  void TankDrive(GenericHID* leftStick, int leftAxis, GenericHID* rightStick,
+                 int rightAxis, bool squaredInputs = true);
+
+  void TankDrive(GenericHID& leftStick, int leftAxis, GenericHID& rightStick,
+                 int rightAxis, bool squaredInputs = true);
+
+  /**
+   * Provide tank steering using the stored robot configuration.
+   *
+   * This function lets you directly provide joystick values from any source.
+   *
+   * @param leftValue  The value of the left stick.
+   * @param rightValue The value of the right stick.
+   * @param squaredInputs If true, the sensitivity will be decreased for small
+   *                      values
+   */
+  void TankDrive(double leftValue, double rightValue,
+                 bool squaredInputs = true);
+
+  /**
+   * Arcade drive implements single stick driving.
+   *
+   * Given a single Joystick, the class assumes the Y axis for the move value
+   * and the X axis for the rotate value. (Should add more information here
+   * regarding the way that arcade drive works.)
+   *
+   * @param stick         The joystick to use for Arcade single-stick driving.
+   *                      The Y-axis will be selected for forwards/backwards and
+   *                      the X-axis will be selected for rotation rate.
+   * @param squaredInputs If true, the sensitivity will be decreased for small
+   *                      values
+   */
+  void ArcadeDrive(GenericHID* stick, bool squaredInputs = true);
+
+  /**
+   * Arcade drive implements single stick driving.
+   *
+   * Given a single Joystick, the class assumes the Y axis for the move value
+   * and the X axis for the rotate value. (Should add more information here
+   * regarding the way that arcade drive works.)
+   *
+   * @param stick         The joystick to use for Arcade single-stick driving.
+   *                      The Y-axis will be selected for forwards/backwards and
+   *                      the X-axis will be selected for rotation rate.
+   * @param squaredInputs If true, the sensitivity will be decreased for small
+   *                      values
+   */
+  void ArcadeDrive(GenericHID& stick, bool squaredInputs = true);
+
+  /**
+   * Arcade drive implements single stick driving.
+   *
+   * Given two joystick instances and two axis, compute the values to send to
+   * either two or four motors.
+   *
+   * @param moveStick     The Joystick object that represents the
+   *                      forward/backward direction
+   * @param moveAxis      The axis on the moveStick object to use for
+   *                      forwards/backwards (typically Y_AXIS)
+   * @param rotateStick   The Joystick object that represents the rotation value
+   * @param rotateAxis    The axis on the rotation object to use for the rotate
+   *                      right/left (typically X_AXIS)
+   * @param squaredInputs Setting this parameter to true increases the
+   *                      sensitivity at lower speeds
+   */
+  void ArcadeDrive(GenericHID* moveStick, int moveChannel,
+                   GenericHID* rotateStick, int rotateChannel,
+                   bool squaredInputs = true);
+
+  /**
+   * Arcade drive implements single stick driving.
+   *
+   * Given two joystick instances and two axis, compute the values to send to
+   * either two or four motors.
+   *
+   * @param moveStick     The Joystick object that represents the
+   *                      forward/backward direction
+   * @param moveAxis      The axis on the moveStick object to use for
+   *                      forwards/backwards (typically Y_AXIS)
+   * @param rotateStick   The Joystick object that represents the rotation value
+   * @param rotateAxis    The axis on the rotation object to use for the rotate
+   *                      right/left (typically X_AXIS)
+   * @param squaredInputs Setting this parameter to true increases the
+   *                      sensitivity at lower speeds
+   */
+  void ArcadeDrive(GenericHID& moveStick, int moveChannel,
+                   GenericHID& rotateStick, int rotateChannel,
+                   bool squaredInputs = true);
+
+  /**
+   * Arcade drive implements single stick driving.
+   *
+   * This function lets you directly provide joystick values from any source.
+   *
+   * @param moveValue     The value to use for fowards/backwards
+   * @param rotateValue   The value to use for the rotate right/left
+   * @param squaredInputs If set, increases the sensitivity at low speeds
+   */
+  void ArcadeDrive(double moveValue, double rotateValue,
+                   bool squaredInputs = true);
+
+  /**
+   * Drive method for Mecanum wheeled robots.
+   *
+   * A method for driving with Mecanum wheeled robots. There are 4 wheels
+   * on the robot, arranged so that the front and back wheels are toed in 45
+   * degrees.
+   * When looking at the wheels from the top, the roller axles should form an X
+   * across the robot.
+   *
+   * This is designed to be directly driven by joystick axes.
+   *
+   * @param x         The speed that the robot should drive in the X direction.
+   *                  [-1.0..1.0]
+   * @param y         The speed that the robot should drive in the Y direction.
+   *                  This input is inverted to match the forward == -1.0 that
+   *                  joysticks produce. [-1.0..1.0]
+   * @param rotation  The rate of rotation for the robot that is completely
+   *                  independent of the translation. [-1.0..1.0]
+   * @param gyroAngle The current angle reading from the gyro.  Use this to
+   *                  implement field-oriented controls.
+   */
+  void MecanumDrive_Cartesian(double x, double y, double rotation,
+                              double gyroAngle = 0.0);
+
+  /**
+   * Drive method for Mecanum wheeled robots.
+   *
+   * A method for driving with Mecanum wheeled robots. There are 4 wheels
+   * on the robot, arranged so that the front and back wheels are toed in 45
+   * degrees.
+   * When looking at the wheels from the top, the roller axles should form an X
+   * across the robot.
+   *
+   * @param magnitude The speed that the robot should drive in a given
+   *                  direction. [-1.0..1.0]
+   * @param direction The direction the robot should drive in degrees. The
+   *                  direction and maginitute are independent of the rotation
+   *                  rate.
+   * @param rotation  The rate of rotation for the robot that is completely
+   *                  independent of the magnitute or direction. [-1.0..1.0]
+   */
+  void MecanumDrive_Polar(double magnitude, double direction, double rotation);
+
+  /**
+   * Holonomic Drive method for Mecanum wheeled robots.
+   *
+   * This is an alias to MecanumDrive_Polar() for backward compatability
+   *
+   * @param magnitude The speed that the robot should drive in a given
+   *                  direction. [-1.0..1.0]
+   * @param direction The direction the robot should drive. The direction and
+   *                  magnitude are independent of the rotation rate.
+   * @param rotation  The rate of rotation for the robot that is completely
+   *                  independent of the magnitude or direction.  [-1.0..1.0]
+   */
+  void HolonomicDrive(double magnitude, double direction, double rotation);
+
+  /**
+   * Set the speed of the right and left motors.
+   *
+   * This is used once an appropriate drive setup function is called such as
+   * TwoWheelDrive(). The motors are set to "leftOutput" and "rightOutput"
+   * and includes flipping the direction of one side for opposing motors.
+   *
+   * @param leftOutput  The speed to send to the left side of the robot.
+   * @param rightOutput The speed to send to the right side of the robot.
+   */
+  virtual void SetLeftRightMotorOutputs(double leftOutput, double rightOutput);
+
+  /*
+   * Invert a motor direction.
+   *
+   * This is used when a motor should run in the opposite direction as the drive
+   * code would normally run it. Motors that are direct drive would be inverted,
+   * the Drive code assumes that the motors are geared with one reversal.
+   *
+   * @param motor      The motor index to invert.
+   * @param isInverted True if the motor should be inverted when operated.
+   */
+  void SetInvertedMotor(MotorType motor, bool isInverted);
+
+  /**
+   * Set the turning sensitivity.
+   *
+   * This only impacts the Drive() entry-point.
+   *
+   * @param sensitivity Effectively sets the turning sensitivity (or turn radius
+   *                    for a given value)
+   */
+  void SetSensitivity(double sensitivity);
+
+  /**
+   * Configure the scaling factor for using RobotDrive with motor controllers in
+   * a mode other than PercentVbus.
+   *
+   * @param maxOutput Multiplied with the output percentage computed by the
+   *                  drive functions.
+   */
+  void SetMaxOutput(double maxOutput);
+
+  void StopMotor() override;
+  void GetDescription(wpi::raw_ostream& desc) const override;
+
+ protected:
+  /**
+   * Common function to initialize all the robot drive constructors.
+   *
+   * Create a motor safety object (the real reason for the common code) and
+   * initialize all the motor assignments. The default timeout is set for the
+   * robot drive.
+   */
+  void InitRobotDrive();
+
+  /**
+   * Limit motor values to the -1.0 to +1.0 range.
+   */
+  double Limit(double number);
+
+  /**
+   * Normalize all wheel speeds if the magnitude of any wheel is greater than
+   * 1.0.
+   */
+  void Normalize(double* wheelSpeeds);
+
+  /**
+   * Rotate a vector in Cartesian space.
+   */
+  void RotateVector(double& x, double& y, double angle);
+
+  static constexpr int kMaxNumberOfMotors = 4;
+
+  double m_sensitivity = 0.5;
+  double m_maxOutput = 1.0;
+
+  std::shared_ptr<SpeedController> m_frontLeftMotor;
+  std::shared_ptr<SpeedController> m_frontRightMotor;
+  std::shared_ptr<SpeedController> m_rearLeftMotor;
+  std::shared_ptr<SpeedController> m_rearRightMotor;
+
+ private:
+  int GetNumMotors() {
+    int motors = 0;
+    if (m_frontLeftMotor) motors++;
+    if (m_frontRightMotor) motors++;
+    if (m_rearLeftMotor) motors++;
+    if (m_rearRightMotor) motors++;
+    return motors;
+  }
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/RobotState.h b/wpilibc/src/main/native/include/frc/RobotState.h
new file mode 100644
index 0000000..60e608a
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/RobotState.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+namespace frc {
+
+class RobotState {
+ public:
+  RobotState() = delete;
+
+  static bool IsDisabled();
+  static bool IsEnabled();
+  static bool IsEStopped();
+  static bool IsOperatorControl();
+  static bool IsAutonomous();
+  static bool IsTest();
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/SD540.h b/wpilibc/src/main/native/include/frc/SD540.h
new file mode 100644
index 0000000..07f7f18
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/SD540.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Mindsensors SD540 Speed Controller.
+ *
+ * Note that the SD540 uses the following bounds for PWM values. These values
+ * should work reasonably well for most controllers, but if users experience
+ * issues such as asymmetric behavior around the deadband or inability to
+ * saturate the controller in either direction, calibration is recommended.
+ * The calibration procedure can be found in the SD540 User Manual available
+ * from Mindsensors.
+ *
+ * \li 2.05ms = full "forward"
+ * \li 1.55ms = the "high end" of the deadband range
+ * \li 1.50ms = center of the deadband range (off)
+ * \li 1.44ms = the "low end" of the deadband range
+ * \li 0.94ms = full "reverse"
+ */
+class SD540 : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a SD540.
+   *
+   * @param channel The PWM channel that the SD540 is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit SD540(int channel);
+
+  SD540(SD540&&) = default;
+  SD540& operator=(SD540&&) = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/SPI.h b/wpilibc/src/main/native/include/frc/SPI.h
new file mode 100644
index 0000000..8e721bc
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/SPI.h
@@ -0,0 +1,428 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+
+#include <hal/SPITypes.h>
+#include <units/units.h>
+#include <wpi/ArrayRef.h>
+#include <wpi/deprecated.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+class DigitalSource;
+
+/**
+ * SPI bus interface class.
+ *
+ * This class is intended to be used by sensor (and other SPI device) drivers.
+ * It probably should not be used directly.
+ *
+ */
+class SPI : public ErrorBase {
+ public:
+  enum Port { kOnboardCS0 = 0, kOnboardCS1, kOnboardCS2, kOnboardCS3, kMXP };
+
+  /**
+   * Constructor
+   *
+   * @param port the physical SPI port
+   */
+  explicit SPI(Port port);
+
+  ~SPI() override;
+
+  SPI(SPI&&) = default;
+  SPI& operator=(SPI&&) = default;
+
+  /**
+   * Configure the rate of the generated clock signal.
+   *
+   * The default value is 500,000Hz.
+   * The maximum value is 4,000,000Hz.
+   *
+   * @param hz The clock rate in Hertz.
+   */
+  void SetClockRate(int hz);
+
+  /**
+   * Configure the order that bits are sent and received on the wire
+   * to be most significant bit first.
+   */
+  void SetMSBFirst();
+
+  /**
+   * Configure the order that bits are sent and received on the wire
+   * to be least significant bit first.
+   */
+  void SetLSBFirst();
+
+  /**
+   * Configure that the data is stable on the leading edge and the data
+   * changes on the trailing edge.
+   */
+  void SetSampleDataOnLeadingEdge();
+
+  /**
+   * Configure that the data is stable on the trailing edge and the data
+   * changes on the leading edge.
+   */
+  void SetSampleDataOnTrailingEdge();
+
+  /**
+   * Configure that the data is stable on the falling edge and the data
+   * changes on the rising edge.
+   */
+  WPI_DEPRECATED("Use SetSampleDataOnTrailingEdge in most cases.")
+  void SetSampleDataOnFalling();
+
+  /**
+   * Configure that the data is stable on the rising edge and the data
+   * changes on the falling edge.
+   */
+  WPI_DEPRECATED("Use SetSampleDataOnLeadingEdge in most cases")
+  void SetSampleDataOnRising();
+
+  /**
+   * Configure the clock output line to be active low.
+   * This is sometimes called clock polarity high or clock idle high.
+   */
+  void SetClockActiveLow();
+
+  /**
+   * Configure the clock output line to be active high.
+   * This is sometimes called clock polarity low or clock idle low.
+   */
+  void SetClockActiveHigh();
+
+  /**
+   * Configure the chip select line to be active high.
+   */
+  void SetChipSelectActiveHigh();
+
+  /**
+   * Configure the chip select line to be active low.
+   */
+  void SetChipSelectActiveLow();
+
+  /**
+   * Write data to the slave device.  Blocks until there is space in the
+   * output FIFO.
+   *
+   * If not running in output only mode, also saves the data received
+   * on the MISO input during the transfer into the receive FIFO.
+   */
+  virtual int Write(uint8_t* data, int size);
+
+  /**
+   * Read a word from the receive FIFO.
+   *
+   * Waits for the current transfer to complete if the receive FIFO is empty.
+   *
+   * If the receive FIFO is empty, there is no active transfer, and initiate
+   * is false, errors.
+   *
+   * @param initiate If true, this function pushes "0" into the transmit buffer
+   *                 and initiates a transfer. If false, this function assumes
+   *                 that data is already in the receive FIFO from a previous
+   *                 write.
+   */
+  virtual int Read(bool initiate, uint8_t* dataReceived, int size);
+
+  /**
+   * Perform a simultaneous read/write transaction with the device
+   *
+   * @param dataToSend   The data to be written out to the device
+   * @param dataReceived Buffer to receive data from the device
+   * @param size         The length of the transaction, in bytes
+   */
+  virtual int Transaction(uint8_t* dataToSend, uint8_t* dataReceived, int size);
+
+  /**
+   * Initialize automatic SPI transfer engine.
+   *
+   * Only a single engine is available, and use of it blocks use of all other
+   * chip select usage on the same physical SPI port while it is running.
+   *
+   * @param bufferSize buffer size in bytes
+   */
+  void InitAuto(int bufferSize);
+
+  /**
+   * Frees the automatic SPI transfer engine.
+   */
+  void FreeAuto();
+
+  /**
+   * Set the data to be transmitted by the engine.
+   *
+   * Up to 16 bytes are configurable, and may be followed by up to 127 zero
+   * bytes.
+   *
+   * @param dataToSend data to send (maximum 16 bytes)
+   * @param zeroSize number of zeros to send after the data
+   */
+  void SetAutoTransmitData(wpi::ArrayRef<uint8_t> dataToSend, int zeroSize);
+
+  /**
+   * Start running the automatic SPI transfer engine at a periodic rate.
+   *
+   * InitAuto() and SetAutoTransmitData() must be called before calling this
+   * function.
+   *
+   * @param period period between transfers (us resolution)
+   */
+  void StartAutoRate(units::second_t period);
+
+  /**
+   * Start running the automatic SPI transfer engine at a periodic rate.
+   *
+   * InitAuto() and SetAutoTransmitData() must be called before calling this
+   * function.
+   *
+   * @param period period between transfers, in seconds (us resolution)
+   */
+  WPI_DEPRECATED("Use StartAutoRate with unit-safety instead")
+  void StartAutoRate(double period);
+
+  /**
+   * Start running the automatic SPI transfer engine when a trigger occurs.
+   *
+   * InitAuto() and SetAutoTransmitData() must be called before calling this
+   * function.
+   *
+   * @param source digital source for the trigger (may be an analog trigger)
+   * @param rising trigger on the rising edge
+   * @param falling trigger on the falling edge
+   */
+  void StartAutoTrigger(DigitalSource& source, bool rising, bool falling);
+
+  /**
+   * Stop running the automatic SPI transfer engine.
+   */
+  void StopAuto();
+
+  /**
+   * Force the engine to make a single transfer.
+   */
+  void ForceAutoRead();
+
+  /**
+   * Read data that has been transferred by the automatic SPI transfer engine.
+   *
+   * Transfers may be made a byte at a time, so it's necessary for the caller
+   * to handle cases where an entire transfer has not been completed.
+   *
+   * Each received data sequence consists of a timestamp followed by the
+   * received data bytes, one byte per word (in the least significant byte).
+   * The length of each received data sequence is the same as the combined
+   * size of the data and zeroSize set in SetAutoTransmitData().
+   *
+   * Blocks until numToRead words have been read or timeout expires.
+   * May be called with numToRead=0 to retrieve how many words are available.
+   *
+   * @param buffer buffer where read words are stored
+   * @param numToRead number of words to read
+   * @param timeout timeout (ms resolution)
+   * @return Number of words remaining to be read
+   */
+  int ReadAutoReceivedData(uint32_t* buffer, int numToRead,
+                           units::second_t timeout);
+
+  /**
+   * Read data that has been transferred by the automatic SPI transfer engine.
+   *
+   * Transfers may be made a byte at a time, so it's necessary for the caller
+   * to handle cases where an entire transfer has not been completed.
+   *
+   * Each received data sequence consists of a timestamp followed by the
+   * received data bytes, one byte per word (in the least significant byte).
+   * The length of each received data sequence is the same as the combined
+   * size of the data and zeroSize set in SetAutoTransmitData().
+   *
+   * Blocks until numToRead words have been read or timeout expires.
+   * May be called with numToRead=0 to retrieve how many words are available.
+   *
+   * @param buffer buffer where read words are stored
+   * @param numToRead number of words to read
+   * @param timeout timeout in seconds (ms resolution)
+   * @return Number of words remaining to be read
+   */
+  WPI_DEPRECATED("Use ReadAutoReceivedData with unit-safety instead")
+  int ReadAutoReceivedData(uint32_t* buffer, int numToRead, double timeout);
+
+  /**
+   * Get the number of bytes dropped by the automatic SPI transfer engine due
+   * to the receive buffer being full.
+   *
+   * @return Number of bytes dropped
+   */
+  int GetAutoDroppedCount();
+
+  /**
+   * Configure the Auto SPI Stall time between reads.
+   *
+   * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for
+   * MXP.
+   * @param csToSclkTicks the number of ticks to wait before asserting the cs
+   * pin
+   * @param stallTicks the number of ticks to stall for
+   * @param pow2BytesPerRead the number of bytes to read before stalling
+   */
+  void ConfigureAutoStall(HAL_SPIPort port, int csToSclkTicks, int stallTicks,
+                          int pow2BytesPerRead);
+
+  /**
+   * Initialize the accumulator.
+   *
+   * @param period    Time between reads
+   * @param cmd       SPI command to send to request data
+   * @param xferSize  SPI transfer size, in bytes
+   * @param validMask Mask to apply to received data for validity checking
+   * @param validData After valid_mask is applied, required matching value for
+   *                  validity checking
+   * @param dataShift Bit shift to apply to received data to get actual data
+   *                  value
+   * @param dataSize  Size (in bits) of data field
+   * @param isSigned  Is data field signed?
+   * @param bigEndian Is device big endian?
+   */
+  void InitAccumulator(units::second_t period, int cmd, int xferSize,
+                       int validMask, int validValue, int dataShift,
+                       int dataSize, bool isSigned, bool bigEndian);
+
+  /**
+   * Initialize the accumulator.
+   *
+   * @param period    Time between reads
+   * @param cmd       SPI command to send to request data
+   * @param xferSize  SPI transfer size, in bytes
+   * @param validMask Mask to apply to received data for validity checking
+   * @param validData After valid_mask is applied, required matching value for
+   *                  validity checking
+   * @param dataShift Bit shift to apply to received data to get actual data
+   *                  value
+   * @param dataSize  Size (in bits) of data field
+   * @param isSigned  Is data field signed?
+   * @param bigEndian Is device big endian?
+   */
+  WPI_DEPRECATED("Use InitAccumulator with unit-safety instead")
+  void InitAccumulator(double period, int cmd, int xferSize, int validMask,
+                       int validValue, int dataShift, int dataSize,
+                       bool isSigned, bool bigEndian);
+
+  /**
+   * Frees the accumulator.
+   */
+  void FreeAccumulator();
+
+  /**
+   * Resets the accumulator to zero.
+   */
+  void ResetAccumulator();
+
+  /**
+   * Set the center value of the accumulator.
+   *
+   * The center value is subtracted from each value before it is added to the
+   * accumulator. This is used for the center value of devices like gyros and
+   * accelerometers to make integration work and to take the device offset into
+   * account when integrating.
+   */
+  void SetAccumulatorCenter(int center);
+
+  /**
+   * Set the accumulator's deadband.
+   */
+  void SetAccumulatorDeadband(int deadband);
+
+  /**
+   * Read the last value read by the accumulator engine.
+   */
+  int GetAccumulatorLastValue() const;
+
+  /**
+   * Read the accumulated value.
+   *
+   * @return The 64-bit value accumulated since the last Reset().
+   */
+  int64_t GetAccumulatorValue() const;
+
+  /**
+   * Read the number of accumulated values.
+   *
+   * Read the count of the accumulated values since the accumulator was last
+   * Reset().
+   *
+   * @return The number of times samples from the channel were accumulated.
+   */
+  int64_t GetAccumulatorCount() const;
+
+  /**
+   * Read the average of the accumulated value.
+   *
+   * @return The accumulated average value (value / count).
+   */
+  double GetAccumulatorAverage() const;
+
+  /**
+   * Read the accumulated value and the number of accumulated values atomically.
+   *
+   * This function reads the value and count atomically.
+   * This can be used for averaging.
+   *
+   * @param value Pointer to the 64-bit accumulated output.
+   * @param count Pointer to the number of accumulation cycles.
+   */
+  void GetAccumulatorOutput(int64_t& value, int64_t& count) const;
+
+  /**
+   * Set the center value of the accumulator integrator.
+   *
+   * The center value is subtracted from each value*dt before it is added to the
+   * integrated value. This is used for the center value of devices like gyros
+   * and accelerometers to take the device offset into account when integrating.
+   */
+  void SetAccumulatorIntegratedCenter(double center);
+
+  /**
+   * Read the integrated value.  This is the sum of (each value * time between
+   * values).
+   *
+   * @return The integrated value accumulated since the last Reset().
+   */
+  double GetAccumulatorIntegratedValue() const;
+
+  /**
+   * Read the average of the integrated value.  This is the sum of (each value
+   * times the time between values), divided by the count.
+   *
+   * @return The average of the integrated value accumulated since the last
+   *         Reset().
+   */
+  double GetAccumulatorIntegratedAverage() const;
+
+ protected:
+  hal::SPIPort m_port;
+  bool m_msbFirst = false;          // Default little-endian
+  bool m_sampleOnTrailing = false;  // Default data updated on falling edge
+  bool m_clockIdleHigh = false;     // Default clock active high
+
+ private:
+  void Init();
+
+  class Accumulator;
+  std::unique_ptr<Accumulator> m_accum;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/SensorUtil.h b/wpilibc/src/main/native/include/frc/SensorUtil.h
new file mode 100644
index 0000000..ab471b1
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/SensorUtil.h
@@ -0,0 +1,116 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+/**
+ * Stores most recent status information as well as containing utility functions
+ * for checking channels and error processing.
+ */
+class SensorUtil final {
+ public:
+  SensorUtil() = delete;
+
+  /**
+   * Get the number of the default solenoid module.
+   *
+   * @return The number of the default solenoid module.
+   */
+  static int GetDefaultSolenoidModule();
+
+  /**
+   * Check that the solenoid module number is valid. module numbers are 0-based
+   *
+   * @return Solenoid module is valid and present
+   */
+  static bool CheckSolenoidModule(int moduleNumber);
+
+  /**
+   * Check that the digital channel number is valid.
+   *
+   * Verify that the channel number is one of the legal channel numbers. Channel
+   * numbers are 0-based.
+   *
+   * @return Digital channel is valid
+   */
+  static bool CheckDigitalChannel(int channel);
+
+  /**
+   * Check that the relay channel number is valid.
+   *
+   * Verify that the channel number is one of the legal channel numbers. Channel
+   * numbers are 0-based.
+   *
+   * @return Relay channel is valid
+   */
+  static bool CheckRelayChannel(int channel);
+
+  /**
+   * Check that the digital channel number is valid.
+   *
+   * Verify that the channel number is one of the legal channel numbers. Channel
+   * numbers are 0-based.
+   *
+   * @return PWM channel is valid
+   */
+  static bool CheckPWMChannel(int channel);
+
+  /**
+   * Check that the analog input number is value.
+   *
+   * Verify that the analog input number is one of the legal channel numbers.
+   * Channel numbers are 0-based.
+   *
+   * @return Analog channel is valid
+   */
+  static bool CheckAnalogInputChannel(int channel);
+
+  /**
+   * Check that the analog output number is valid.
+   *
+   * Verify that the analog output number is one of the legal channel numbers.
+   * Channel numbers are 0-based.
+   *
+   * @return Analog channel is valid
+   */
+  static bool CheckAnalogOutputChannel(int channel);
+
+  /**
+   * Verify that the solenoid channel number is within limits.
+   *
+   * @return Solenoid channel is valid
+   */
+  static bool CheckSolenoidChannel(int channel);
+
+  /**
+   * Verify that the power distribution channel number is within limits.
+   *
+   * @return PDP channel is valid
+   */
+  static bool CheckPDPChannel(int channel);
+
+  /**
+   * Verify that the PDP module number is within limits. module numbers are
+   * 0-based
+   *
+   * @return PDP module is valid
+   */
+  static bool CheckPDPModule(int module);
+
+  static const int kDigitalChannels;
+  static const int kAnalogInputs;
+  static const int kAnalogOutputs;
+  static const int kSolenoidChannels;
+  static const int kSolenoidModules;
+  static const int kPwmChannels;
+  static const int kRelayChannels;
+  static const int kPDPChannels;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/SerialPort.h b/wpilibc/src/main/native/include/frc/SerialPort.h
new file mode 100644
index 0000000..f9edb84
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/SerialPort.h
@@ -0,0 +1,223 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared 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 <hal/Types.h>
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/deprecated.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+/**
+ * Driver for the RS-232 serial port on the roboRIO.
+ *
+ * The current implementation uses the VISA formatted I/O mode.  This means that
+ * all traffic goes through the fomatted buffers.  This allows the intermingled
+ * use of Printf(), Scanf(), and the raw buffer accessors Read() and Write().
+ *
+ * More information can be found in the NI-VISA User Manual here:
+ *   http://www.ni.com/pdf/manuals/370423a.pdf
+ * and the NI-VISA Programmer's Reference Manual here:
+ *   http://www.ni.com/pdf/manuals/370132c.pdf
+ */
+class SerialPort : public ErrorBase {
+ public:
+  enum Parity {
+    kParity_None = 0,
+    kParity_Odd = 1,
+    kParity_Even = 2,
+    kParity_Mark = 3,
+    kParity_Space = 4
+  };
+
+  enum StopBits {
+    kStopBits_One = 10,
+    kStopBits_OnePointFive = 15,
+    kStopBits_Two = 20
+  };
+
+  enum FlowControl {
+    kFlowControl_None = 0,
+    kFlowControl_XonXoff = 1,
+    kFlowControl_RtsCts = 2,
+    kFlowControl_DtrDsr = 4
+  };
+
+  enum WriteBufferMode { kFlushOnAccess = 1, kFlushWhenFull = 2 };
+
+  enum Port { kOnboard = 0, kMXP = 1, kUSB = 2, kUSB1 = 2, kUSB2 = 3 };
+
+  /**
+   * Create an instance of a Serial Port class.
+   *
+   * @param baudRate The baud rate to configure the serial port.
+   * @param port     The physical port to use
+   * @param dataBits The number of data bits per transfer.  Valid values are
+   *                 between 5 and 8 bits.
+   * @param parity   Select the type of parity checking to use.
+   * @param stopBits The number of stop bits to use as defined by the enum
+   *                 StopBits.
+   */
+  SerialPort(int baudRate, Port port = kOnboard, int dataBits = 8,
+             Parity parity = kParity_None, StopBits stopBits = kStopBits_One);
+
+  /**
+   * Create an instance of a Serial Port class.
+   *
+   * Prefer to use the constructor that doesn't take a port name, but in some
+   * cases the automatic detection might not work correctly.
+   *
+   * @param baudRate The baud rate to configure the serial port.
+   * @param port     The physical port to use
+   * @param portName The direct port name to use
+   * @param dataBits The number of data bits per transfer.  Valid values are
+   *                 between 5 and 8 bits.
+   * @param parity   Select the type of parity checking to use.
+   * @param stopBits The number of stop bits to use as defined by the enum
+   *                 StopBits.
+   */
+  SerialPort(int baudRate, const wpi::Twine& portName, Port port = kOnboard,
+             int dataBits = 8, Parity parity = kParity_None,
+             StopBits stopBits = kStopBits_One);
+
+  ~SerialPort();
+
+  SerialPort(SerialPort&& rhs) = default;
+  SerialPort& operator=(SerialPort&& rhs) = default;
+
+  /**
+   * Set the type of flow control to enable on this port.
+   *
+   * By default, flow control is disabled.
+   */
+  void SetFlowControl(FlowControl flowControl);
+
+  /**
+   * Enable termination and specify the termination character.
+   *
+   * Termination is currently only implemented for receive.
+   * When the the terminator is recieved, the Read() or Scanf() will return
+   * fewer bytes than requested, stopping after the terminator.
+   *
+   * @param terminator The character to use for termination.
+   */
+  void EnableTermination(char terminator = '\n');
+
+  /**
+   * Disable termination behavior.
+   */
+  void DisableTermination();
+
+  /**
+   * Get the number of bytes currently available to read from the serial port.
+   *
+   * @return The number of bytes available to read
+   */
+  int GetBytesReceived();
+
+  /**
+   * Read raw bytes out of the buffer.
+   *
+   * @param buffer Pointer to the buffer to store the bytes in.
+   * @param count  The maximum number of bytes to read.
+   * @return The number of bytes actually read into the buffer.
+   */
+  int Read(char* buffer, int count);
+
+  /**
+   * Write raw bytes to the buffer.
+   *
+   * @param buffer Pointer to the buffer to read the bytes from.
+   * @param count  The maximum number of bytes to write.
+   * @return The number of bytes actually written into the port.
+   */
+  int Write(const char* buffer, int count);
+
+  /**
+   * Write raw bytes to the buffer.
+   *
+   * Use Write({data, len}) to get a buffer that is shorter than the length of
+   * the string.
+   *
+   * @param buffer StringRef to the buffer to read the bytes from.
+   * @return The number of bytes actually written into the port.
+   */
+  int Write(wpi::StringRef buffer);
+
+  /**
+   * Configure the timeout of the serial port.
+   *
+   * This defines the timeout for transactions with the hardware.
+   * It will affect reads and very large writes.
+   *
+   * @param timeout The number of seconds to to wait for I/O.
+   */
+  void SetTimeout(double timeout);
+
+  /**
+   * Specify the size of the input buffer.
+   *
+   * Specify the amount of data that can be stored before data
+   * from the device is returned to Read or Scanf.  If you want
+   * data that is recieved to be returned immediately, set this to 1.
+   *
+   * It the buffer is not filled before the read timeout expires, all
+   * data that has been received so far will be returned.
+   *
+   * @param size The read buffer size.
+   */
+  void SetReadBufferSize(int size);
+
+  /**
+   * Specify the size of the output buffer.
+   *
+   * Specify the amount of data that can be stored before being
+   * transmitted to the device.
+   *
+   * @param size The write buffer size.
+   */
+  void SetWriteBufferSize(int size);
+
+  /**
+   * Specify the flushing behavior of the output buffer.
+   *
+   * When set to kFlushOnAccess, data is synchronously written to the serial
+   * port after each call to either Printf() or Write().
+   *
+   * When set to kFlushWhenFull, data will only be written to the serial port
+   * when the buffer is full or when Flush() is called.
+   *
+   * @param mode The write buffer mode.
+   */
+  void SetWriteBufferMode(WriteBufferMode mode);
+
+  /**
+   * Force the output buffer to be written to the port.
+   *
+   * This is used when SetWriteBufferMode() is set to kFlushWhenFull to force a
+   * flush before the buffer is full.
+   */
+  void Flush();
+
+  /**
+   * Reset the serial port driver to a known state.
+   *
+   * Empty the transmit and receive buffers in the device and formatted I/O.
+   */
+  void Reset();
+
+ private:
+  hal::Handle<HAL_SerialPortHandle> m_portHandle;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Servo.h b/wpilibc/src/main/native/include/frc/Servo.h
new file mode 100644
index 0000000..16b4281
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Servo.h
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWM.h"
+#include "frc/SpeedController.h"
+
+namespace frc {
+
+/**
+ * Standard hobby style servo.
+ *
+ * The range parameters default to the appropriate values for the Hitec HS-322HD
+ * servo provided in the FIRST Kit of Parts in 2008.
+ */
+class Servo : public PWM {
+ public:
+  /**
+   * @param channel The PWM channel to which the servo is attached. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit Servo(int channel);
+
+  Servo(Servo&&) = default;
+  Servo& operator=(Servo&&) = default;
+
+  /**
+   * Set the servo position.
+   *
+   * Servo values range from 0.0 to 1.0 corresponding to the range of full left
+   * to full right.
+   *
+   * @param value Position from 0.0 to 1.0.
+   */
+  void Set(double value);
+
+  /**
+   * Set the servo to offline.
+   *
+   * Set the servo raw value to 0 (undriven)
+   */
+  void SetOffline();
+
+  /**
+   * Get the servo position.
+   *
+   * Servo values range from 0.0 to 1.0 corresponding to the range of full left
+   * to full right.
+   *
+   * @return Position from 0.0 to 1.0.
+   */
+  double Get() const;
+
+  /**
+   * Set the servo angle.
+   *
+   * Assume that the servo angle is linear with respect to the PWM value (big
+   * assumption, need to test).
+   *
+   * Servo angles that are out of the supported range of the servo simply
+   * "saturate" in that direction. In other words, if the servo has a range of
+   * (X degrees to Y degrees) than angles of less than X result in an angle of
+   * X being set and angles of more than Y degrees result in an angle of Y being
+   * set.
+   *
+   * @param degrees The angle in degrees to set the servo.
+   */
+  void SetAngle(double angle);
+
+  /**
+   * Get the servo angle.
+   *
+   * Assume that the servo angle is linear with respect to the PWM value (big
+   * assumption, need to test).
+   *
+   * @return The angle in degrees to which the servo is set.
+   */
+  double GetAngle() const;
+
+  /**
+   * Get the maximum angle of the servo.
+   *
+   * @return The maximum angle of the servo in degrees.
+   */
+  double GetMaxAngle() const;
+
+  /**
+   * Get the minimum angle of the servo.
+   *
+   * @return The minimum angle of the servo in degrees.
+   */
+  double GetMinAngle() const;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  double GetServoAngleRange() const;
+
+  static constexpr double kMaxServoAngle = 180.0;
+  static constexpr double kMinServoAngle = 0.0;
+
+  static constexpr double kDefaultMaxServoPWM = 2.4;
+  static constexpr double kDefaultMinServoPWM = 0.6;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/SlewRateLimiter.h b/wpilibc/src/main/native/include/frc/SlewRateLimiter.h
new file mode 100644
index 0000000..7236a30
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/SlewRateLimiter.h
@@ -0,0 +1,74 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc2/Timer.h>
+
+#include <algorithm>
+
+#include <units/units.h>
+
+namespace frc {
+/**
+ * A class that limits the rate of change of an input value.  Useful for
+ * implementing voltage, setpoint, and/or output ramps.  A slew-rate limit
+ * is most appropriate when the quantity being controlled is a velocity or
+ * a voltage; when controlling a position, consider using a TrapezoidProfile
+ * instead.
+ *
+ * @see TrapezoidProfile
+ */
+template <class Unit>
+class SlewRateLimiter {
+  using Unit_t = units::unit_t<Unit>;
+  using Rate = units::compound_unit<Unit, units::inverse<units::seconds>>;
+  using Rate_t = units::unit_t<Rate>;
+
+ public:
+  /**
+   * Creates a new SlewRateLimiter with the given rate limit and initial value.
+   *
+   * @param rateLimit The rate-of-change limit.
+   * @param initialValue The initial value of the input.
+   */
+  explicit SlewRateLimiter(Rate_t rateLimit, Unit_t initialValue = Unit_t{0})
+      : m_rateLimit{rateLimit}, m_prevVal{initialValue} {
+    m_timer.Start();
+  }
+
+  /**
+   * Filters the input to limit its slew rate.
+   *
+   * @param input The input value whose slew rate is to be limited.
+   * @return The filtered value, which will not change faster than the slew
+   * rate.
+   */
+  Unit_t Calculate(Unit_t input) {
+    m_prevVal += std::clamp(input - m_prevVal, -m_rateLimit * m_timer.Get(),
+                            m_rateLimit * m_timer.Get());
+    m_timer.Reset();
+    return m_prevVal;
+  }
+
+  /**
+   * Resets the slew rate limiter to the specified value; ignores the rate limit
+   * when doing so.
+   *
+   * @param value The value to reset to.
+   */
+  void Reset(Unit_t value) {
+    m_timer.Reset();
+    m_prevVal = value;
+  }
+
+ private:
+  frc2::Timer m_timer;
+  Rate_t m_rateLimit;
+  Unit_t m_prevVal;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Solenoid.h b/wpilibc/src/main/native/include/frc/Solenoid.h
new file mode 100644
index 0000000..86a2839
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Solenoid.h
@@ -0,0 +1,103 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/SolenoidBase.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBuilder;
+
+/**
+ * Solenoid class for running high voltage Digital Output (PCM).
+ *
+ * The Solenoid class is typically used for pneumatics solenoids, but could be
+ * used for any device within the current spec of the PCM.
+ */
+class Solenoid : public SolenoidBase,
+                 public Sendable,
+                 public SendableHelper<Solenoid> {
+ public:
+  /**
+   * Constructor using the default PCM ID (0).
+   *
+   * @param channel The channel on the PCM to control (0..7).
+   */
+  explicit Solenoid(int channel);
+
+  /**
+   * Constructor.
+   *
+   * @param moduleNumber The CAN ID of the PCM the solenoid is attached to
+   * @param channel      The channel on the PCM to control (0..7).
+   */
+  Solenoid(int moduleNumber, int channel);
+
+  ~Solenoid() override;
+
+  Solenoid(Solenoid&&) = default;
+  Solenoid& operator=(Solenoid&&) = default;
+
+  /**
+   * Set the value of a solenoid.
+   *
+   * @param on Turn the solenoid output off or on.
+   */
+  virtual void Set(bool on);
+
+  /**
+   * Read the current value of the solenoid.
+   *
+   * @return The current value of the solenoid.
+   */
+  virtual bool Get() const;
+
+  /**
+   * Check if solenoid is blacklisted.
+   *
+   * If a solenoid is shorted, it is added to the blacklist and
+   * disabled until power cycle, or until faults are cleared.
+   *
+   * @see ClearAllPCMStickyFaults()
+   *
+   * @return If solenoid is disabled due to short.
+   */
+  bool IsBlackListed() const;
+
+  /**
+   * Set the pulse duration in the PCM. This is used in conjunction with
+   * the startPulse method to allow the PCM to control the timing of a pulse.
+   * The timing can be controlled in 0.01 second increments.
+   *
+   * @param durationSeconds The duration of the pulse, from 0.01 to 2.55
+   *                        seconds.
+   *
+   * @see startPulse()
+   */
+  void SetPulseDuration(double durationSeconds);
+
+  /**
+   * Trigger the PCM to generate a pulse of the duration set in
+   * setPulseDuration.
+   *
+   * @see setPulseDuration()
+   */
+  void StartPulse();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  hal::Handle<HAL_SolenoidHandle> m_solenoidHandle;
+  int m_channel;  // The channel on the module to control
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/SolenoidBase.h b/wpilibc/src/main/native/include/frc/SolenoidBase.h
new file mode 100644
index 0000000..314df5c
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/SolenoidBase.h
@@ -0,0 +1,127 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+/**
+ * SolenoidBase class is the common base class for the Solenoid and
+ * DoubleSolenoid classes.
+ */
+class SolenoidBase : public ErrorBase {
+ public:
+  /**
+   * Read all 8 solenoids as a single byte
+   *
+   * @param module the module to read from
+   * @return The current value of all 8 solenoids on the module.
+   */
+  static int GetAll(int module);
+
+  /**
+   * Read all 8 solenoids as a single byte
+   *
+   * @return The current value of all 8 solenoids on the module.
+   */
+  int GetAll() const;
+
+  /**
+   * Reads complete solenoid blacklist for all 8 solenoids as a single byte.
+   *
+   * If a solenoid is shorted, it is added to the blacklist and
+   * disabled until power cycle, or until faults are cleared.
+   * @see ClearAllPCMStickyFaults()
+   *
+   * @param module the module to read from
+   * @return The solenoid blacklist of all 8 solenoids on the module.
+   */
+  static int GetPCMSolenoidBlackList(int module);
+
+  /**
+   * Reads complete solenoid blacklist for all 8 solenoids as a single byte.
+   *
+   * If a solenoid is shorted, it is added to the blacklist and
+   * disabled until power cycle, or until faults are cleared.
+   * @see ClearAllPCMStickyFaults()
+   *
+   * @return The solenoid blacklist of all 8 solenoids on the module.
+   */
+  int GetPCMSolenoidBlackList() const;
+
+  /**
+   * @param module the module to read from
+   * @return true if PCM sticky fault is set : The common highside solenoid
+   *         voltage rail is too low, most likely a solenoid channel is shorted.
+   */
+  static bool GetPCMSolenoidVoltageStickyFault(int module);
+
+  /**
+   * @return true if PCM sticky fault is set : The common highside solenoid
+   *         voltage rail is too low, most likely a solenoid channel is shorted.
+   */
+  bool GetPCMSolenoidVoltageStickyFault() const;
+
+  /**
+   * @param module the module to read from
+   * @return true if PCM is in fault state : The common highside solenoid
+   *         voltage rail is too low, most likely a solenoid channel is shorted.
+   */
+  static bool GetPCMSolenoidVoltageFault(int module);
+
+  /**
+   * @return true if PCM is in fault state : The common highside solenoid
+   *         voltage rail is too low, most likely a solenoid channel is shorted.
+   */
+  bool GetPCMSolenoidVoltageFault() const;
+
+  /**
+   * Clear ALL sticky faults inside PCM that Compressor is wired to.
+   *
+   * If a sticky fault is set, then it will be persistently cleared.  Compressor
+   * drive maybe momentarily disable while flags are being cleared. Care should
+   * be taken to not call this too frequently, otherwise normal compressor
+   * functionality may be prevented.
+   *
+   * If no sticky faults are set then this call will have no effect.
+   *
+   * @param module the module to read from
+   */
+  static void ClearAllPCMStickyFaults(int module);
+
+  /**
+   * Clear ALL sticky faults inside PCM that Compressor is wired to.
+   *
+   * If a sticky fault is set, then it will be persistently cleared.  Compressor
+   * drive maybe momentarily disable while flags are being cleared. Care should
+   * be taken to not call this too frequently, otherwise normal compressor
+   * functionality may be prevented.
+   *
+   * If no sticky faults are set then this call will have no effect.
+   */
+  void ClearAllPCMStickyFaults();
+
+ protected:
+  /**
+   * Constructor.
+   *
+   * @param moduleNumber The CAN PCM ID.
+   */
+  explicit SolenoidBase(int pcmID);
+
+  SolenoidBase(SolenoidBase&&) = default;
+  SolenoidBase& operator=(SolenoidBase&&) = default;
+
+  static constexpr int m_maxModules = 63;
+  static constexpr int m_maxPorts = 8;
+
+  int m_moduleNumber;  // PCM module number
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Spark.h b/wpilibc/src/main/native/include/frc/Spark.h
new file mode 100644
index 0000000..24ed8f5
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Spark.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * REV Robotics SPARK Speed Controller.
+ *
+ * Note that the SPARK uses the following bounds for PWM values. These values
+ * should work reasonably well for most controllers, but if users experience
+ * issues such as asymmetric behavior around the deadband or inability to
+ * saturate the controller in either direction, calibration is recommended.
+ * The calibration procedure can be found in the SPARK User Manual available
+ * from REV Robotics.
+ *
+ * \li 2.003ms = full "forward"
+ * \li 1.550ms = the "high end" of the deadband range
+ * \li 1.500ms = center of the deadband range (off)
+ * \li 1.460ms = the "low end" of the deadband range
+ * \li 0.999ms = full "reverse"
+ */
+class Spark : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a SPARK.
+   *
+   * @param channel The PWM channel that the SPARK is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit Spark(int channel);
+
+  Spark(Spark&&) = default;
+  Spark& operator=(Spark&&) = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/SpeedController.h b/wpilibc/src/main/native/include/frc/SpeedController.h
new file mode 100644
index 0000000..2b11aee
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/SpeedController.h
@@ -0,0 +1,76 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+
+#include "frc/PIDOutput.h"
+
+namespace frc {
+
+/**
+ * Interface for speed controlling devices.
+ */
+class SpeedController : public PIDOutput {
+ public:
+  virtual ~SpeedController() = default;
+
+  /**
+   * Common interface for setting the speed of a speed controller.
+   *
+   * @param speed The speed to set.  Value should be between -1.0 and 1.0.
+   */
+  virtual void Set(double speed) = 0;
+
+  /**
+   * Sets the voltage output of the SpeedController.  Compensates for
+   * the current bus voltage to ensure that the desired voltage is output even
+   * if the battery voltage is below 12V - highly useful when the voltage
+   * outputs are "meaningful" (e.g. they come from a feedforward calculation).
+   *
+   * <p>NOTE: This function *must* be called regularly in order for voltage
+   * compensation to work properly - unlike the ordinary set function, it is not
+   * "set it and forget it."
+   *
+   * @param output The voltage to output.
+   */
+  virtual void SetVoltage(units::volt_t output);
+
+  /**
+   * Common interface for getting the current set speed of a speed controller.
+   *
+   * @return The current set speed.  Value is between -1.0 and 1.0.
+   */
+  virtual double Get() const = 0;
+
+  /**
+   * Common interface for inverting direction of a speed controller.
+   *
+   * @param isInverted The state of inversion, true is inverted.
+   */
+  virtual void SetInverted(bool isInverted) = 0;
+
+  /**
+   * Common interface for returning the inversion state of a speed controller.
+   *
+   * @return isInverted The state of inversion, true is inverted.
+   */
+  virtual bool GetInverted() const = 0;
+
+  /**
+   * Common interface for disabling a motor.
+   */
+  virtual void Disable() = 0;
+
+  /**
+   * Common interface to stop the motor until Set is called again.
+   */
+  virtual void StopMotor() = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h b/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h
new file mode 100644
index 0000000..80adf1c
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+#include <vector>
+
+#include "frc/SpeedController.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SpeedControllerGroup : public Sendable,
+                             public SpeedController,
+                             public SendableHelper<SpeedControllerGroup> {
+ public:
+  template <class... SpeedControllers>
+  explicit SpeedControllerGroup(SpeedController& speedController,
+                                SpeedControllers&... speedControllers);
+  ~SpeedControllerGroup() override = default;
+
+  SpeedControllerGroup(SpeedControllerGroup&&) = default;
+  SpeedControllerGroup& operator=(SpeedControllerGroup&&) = default;
+
+  void Set(double speed) override;
+  double Get() const override;
+  void SetInverted(bool isInverted) override;
+  bool GetInverted() const override;
+  void Disable() override;
+  void StopMotor() override;
+  void PIDWrite(double output) override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  bool m_isInverted = false;
+  std::vector<std::reference_wrapper<SpeedController>> m_speedControllers;
+};
+
+}  // namespace frc
+
+#include "frc/SpeedControllerGroup.inc"
diff --git a/wpilibc/src/main/native/include/frc/SpeedControllerGroup.inc b/wpilibc/src/main/native/include/frc/SpeedControllerGroup.inc
new file mode 100644
index 0000000..5848746
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/SpeedControllerGroup.inc
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+namespace frc {
+
+template <class... SpeedControllers>
+SpeedControllerGroup::SpeedControllerGroup(
+    SpeedController& speedController, SpeedControllers&... speedControllers)
+    : m_speedControllers{speedController, speedControllers...} {
+  for (auto& speedController : m_speedControllers)
+    SendableRegistry::GetInstance().AddChild(this, &speedController.get());
+  static int instances = 0;
+  ++instances;
+  SendableRegistry::GetInstance().Add(this, "SpeedControllerGroup", instances);
+}
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Talon.h b/wpilibc/src/main/native/include/frc/Talon.h
new file mode 100644
index 0000000..6e92dfc
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Talon.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Cross the Road Electronics (CTRE) Talon and Talon SR Speed Controller.
+ *
+ * Note that the Talon uses the following bounds for PWM values. These values
+ * should work reasonably well for most controllers, but if users experience
+ * issues such as asymmetric behavior around the deadband or inability to
+ * saturate the controller in either direction, calibration is recommended.
+ * The calibration procedure can be found in the Talon User Manual available
+ * from CTRE.
+ *
+ * \li 2.037ms = full "forward"
+ * \li 1.539ms = the "high end" of the deadband range
+ * \li 1.513ms = center of the deadband range (off)
+ * \li 1.487ms = the "low end" of the deadband range
+ * \li 0.989ms = full "reverse"
+ */
+class Talon : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a Talon (original or Talon SR).
+   *
+   * @param channel The PWM channel number that the Talon is attached to. 0-9
+   *                are on-board, 10-19 are on the MXP port
+   */
+  explicit Talon(int channel);
+
+  Talon(Talon&&) = default;
+  Talon& operator=(Talon&&) = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Threads.h b/wpilibc/src/main/native/include/frc/Threads.h
new file mode 100644
index 0000000..3c44961
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Threads.h
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <thread>
+
+namespace frc {
+
+/**
+ * Get the thread priority for the specified thread.
+ *
+ * @param thread     Reference to the thread to get the priority for.
+ * @param isRealTime Set to true if thread is realtime, otherwise false.
+ * @return The current thread priority. Scaled 1-99, with 1 being highest.
+ */
+int GetThreadPriority(std::thread& thread, bool* isRealTime);
+
+/**
+ * Get the thread priority for the current thread
+ *
+ * @param isRealTime Set to true if thread is realtime, otherwise false.
+ * @return The current thread priority. Scaled 1-99.
+ */
+int GetCurrentThreadPriority(bool* isRealTime);
+
+/**
+ * Sets the thread priority for the specified thread
+ *
+ * @param thread   Reference to the thread to set the priority of.
+ * @param realTime Set to true to set a realtime priority, false for standard
+ *                 priority.
+ * @param priority Priority to set the thread to. Scaled 1-99, with 1 being
+ *                 highest. On RoboRIO, priority is ignored for non realtime
+ *                 setting.
+ *
+ * @return The success state of setting the priority
+ */
+bool SetThreadPriority(std::thread& thread, bool realTime, int priority);
+
+/**
+ * Sets the thread priority for the current thread
+ *
+ * @param realTime Set to true to set a realtime priority, false for standard
+ *                 priority.
+ * @param priority Priority to set the thread to. Scaled 1-99, with 1 being
+ *                 highest. On RoboRIO, priority is ignored for non realtime
+ *                 setting.
+ *
+ * @return The success state of setting the priority
+ */
+bool SetCurrentThreadPriority(bool realTime, int priority);
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/TimedRobot.h b/wpilibc/src/main/native/include/frc/TimedRobot.h
new file mode 100644
index 0000000..112e2c9
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/TimedRobot.h
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+#include <units/units.h>
+#include <wpi/deprecated.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/IterativeRobotBase.h"
+
+namespace frc {
+
+/**
+ * TimedRobot implements the IterativeRobotBase robot program framework.
+ *
+ * The TimedRobot class is intended to be subclassed by a user creating a
+ * robot program.
+ *
+ * Periodic() functions from the base class are called on an interval by a
+ * Notifier instance.
+ */
+class TimedRobot : public IterativeRobotBase, public ErrorBase {
+ public:
+  static constexpr units::second_t kDefaultPeriod = 20_ms;
+
+  /**
+   * Provide an alternate "main loop" via StartCompetition().
+   */
+  void StartCompetition() override;
+
+  /**
+   * Ends the main loop in StartCompetition().
+   */
+  void EndCompetition() override;
+
+  /**
+   * Get the time period between calls to Periodic() functions.
+   */
+  units::second_t GetPeriod() const;
+
+  /**
+   * Constructor for TimedRobot.
+   *
+   * @param period Period in seconds.
+   */
+  WPI_DEPRECATED("Use constructor with unit-safety instead.")
+  explicit TimedRobot(double period);
+
+  /**
+   * Constructor for TimedRobot.
+   *
+   * @param period Period.
+   */
+  explicit TimedRobot(units::second_t period = kDefaultPeriod);
+
+  ~TimedRobot() override;
+
+  TimedRobot(TimedRobot&&) = default;
+  TimedRobot& operator=(TimedRobot&&) = default;
+
+ private:
+  hal::Handle<HAL_NotifierHandle> m_notifier;
+
+  // The absolute expiration time
+  units::second_t m_expirationTime{0};
+
+  /**
+   * Update the HAL alarm time.
+   */
+  void UpdateAlarm();
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Timer.h b/wpilibc/src/main/native/include/frc/Timer.h
new file mode 100644
index 0000000..99caa47
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Timer.h
@@ -0,0 +1,142 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+#include <wpi/deprecated.h>
+#include <wpi/mutex.h>
+
+#include "frc/Base.h"
+#include "frc2/Timer.h"
+
+namespace frc {
+
+/**
+ * Pause the task for a specified time.
+ *
+ * Pause the execution of the program for a specified period of time given in
+ * seconds. Motors will continue to run at their last assigned values, and
+ * sensors will continue to update. Only the task containing the wait will pause
+ * until the wait time is expired.
+ *
+ * @param seconds Length of time to pause, in seconds.
+ */
+void Wait(double seconds);
+
+/**
+ * @brief  Gives real-time clock system time with nanosecond resolution
+ * @return The time, just in case you want the robot to start autonomous at 8pm
+ *         on Saturday.
+ */
+double GetTime();
+
+/**
+ * Timer objects measure accumulated time in seconds.
+ *
+ * The timer object functions like a stopwatch. It can be started, stopped, and
+ * cleared. When the timer is running its value counts up in seconds. When
+ * stopped, the timer holds the current value. The implementation simply records
+ * the time when started and subtracts the current time whenever the value is
+ * requested.
+ */
+class Timer {
+ public:
+  /**
+   * Create a new timer object.
+   *
+   * Create a new timer object and reset the time to zero. The timer is
+   * initially not running and must be started.
+   */
+  Timer();
+
+  virtual ~Timer() = default;
+
+  Timer(const Timer& rhs) = default;
+  Timer& operator=(const Timer& rhs) = default;
+  Timer(Timer&& rhs) = default;
+  Timer& operator=(Timer&& rhs) = default;
+
+  /**
+   * Get the current time from the timer. If the clock is running it is derived
+   * from the current system clock the start time stored in the timer class. If
+   * the clock is not running, then return the time when it was last stopped.
+   *
+   * @return Current time value for this timer in seconds
+   */
+  double Get() const;
+
+  /**
+   * Reset the timer by setting the time to 0.
+   *
+   * Make the timer startTime the current time so new requests will be relative
+   * to now.
+   */
+  void Reset();
+
+  /**
+   * Start the timer running.
+   *
+   * Just set the running flag to true indicating that all time requests should
+   * be relative to the system clock.
+   */
+  void Start();
+
+  /**
+   * Stop the timer.
+   *
+   * This computes the time as of now and clears the running flag, causing all
+   * subsequent time requests to be read from the accumulated time rather than
+   * looking at the system clock.
+   */
+  void Stop();
+
+  /**
+   * Check if the period specified has passed and if it has, advance the start
+   * time by that period. This is useful to decide if it's time to do periodic
+   * work without drifting later by the time it took to get around to checking.
+   *
+   * @param period The period to check for (in seconds).
+   * @return       True if the period has passed.
+   */
+  bool HasPeriodPassed(double period);
+
+  /**
+   * Return the FPGA system clock time in seconds.
+   *
+   * Return the time from the FPGA hardware clock in seconds since the FPGA
+   * started. Rolls over after 71 minutes.
+   *
+   * @returns Robot running time in seconds.
+   */
+  static double GetFPGATimestamp();
+
+  /**
+   * Return the approximate match time.
+   *
+   * The FMS does not send an official match time to the robots, but does send
+   * an approximate match time. The value will count down the time remaining in
+   * the current period (auto or teleop).
+   *
+   * Warning: This is not an official time (so it cannot be used to dispute ref
+   * calls or guarantee that a function will trigger before the match ends).
+   *
+   * The Practice Match function of the DS approximates the behavior seen on the
+   * field.
+   *
+   * @return Time remaining in current match period (auto or teleop)
+   */
+  static double GetMatchTime();
+
+  // The time, in seconds, at which the 32-bit FPGA timestamp rolls over to 0
+  static const double kRolloverTime;
+
+ private:
+  frc2::Timer m_timer;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Ultrasonic.h b/wpilibc/src/main/native/include/frc/Ultrasonic.h
new file mode 100644
index 0000000..637c6fc
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Ultrasonic.h
@@ -0,0 +1,241 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+#include <memory>
+#include <thread>
+#include <vector>
+
+#include <hal/SimDevice.h>
+
+#include "frc/Counter.h"
+#include "frc/ErrorBase.h"
+#include "frc/PIDSource.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class DigitalInput;
+class DigitalOutput;
+
+/**
+ * Ultrasonic rangefinder class.
+ *
+ * The Ultrasonic rangefinder measures absolute distance based on the round-trip
+ * time of a ping generated by the controller. These sensors use two
+ * transducers, a speaker and a microphone both tuned to the ultrasonic range. A
+ * common ultrasonic sensor, the Daventech SRF04 requires a short pulse to be
+ * generated on a digital channel. This causes the chirp to be emitted. A second
+ * line becomes high as the ping is transmitted and goes low when the echo is
+ * received. The time that the line is high determines the round trip distance
+ * (time of flight).
+ */
+class Ultrasonic : public ErrorBase,
+                   public Sendable,
+                   public PIDSource,
+                   public SendableHelper<Ultrasonic> {
+ public:
+  enum DistanceUnit { kInches = 0, kMilliMeters = 1 };
+
+  /**
+   * Create an instance of the Ultrasonic Sensor.
+   *
+   * This is designed to support the Daventech SRF04 and Vex ultrasonic sensors.
+   *
+   * @param pingChannel The digital output channel that sends the pulse to
+   *                    initiate the sensor sending the ping.
+   * @param echoChannel The digital input channel that receives the echo. The
+   *                    length of time that the echo is high represents the
+   *                    round trip time of the ping, and the distance.
+   * @param units       The units returned in either kInches or kMilliMeters
+   */
+  Ultrasonic(int pingChannel, int echoChannel, DistanceUnit units = kInches);
+
+  /**
+   * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
+   * channel and a DigitalOutput for the ping channel.
+   *
+   * @param pingChannel The digital output object that starts the sensor doing a
+   *                    ping. Requires a 10uS pulse to start.
+   * @param echoChannel The digital input object that times the return pulse to
+   *                    determine the range.
+   * @param units       The units returned in either kInches or kMilliMeters
+   */
+  Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel,
+             DistanceUnit units = kInches);
+
+  /**
+   * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
+   * channel and a DigitalOutput for the ping channel.
+   *
+   * @param pingChannel The digital output object that starts the sensor doing a
+   *                    ping. Requires a 10uS pulse to start.
+   * @param echoChannel The digital input object that times the return pulse to
+   *                    determine the range.
+   * @param units       The units returned in either kInches or kMilliMeters
+   */
+  Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel,
+             DistanceUnit units = kInches);
+
+  /**
+   * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
+   * channel and a DigitalOutput for the ping channel.
+   *
+   * @param pingChannel The digital output object that starts the sensor doing a
+   *                    ping. Requires a 10uS pulse to start.
+   * @param echoChannel The digital input object that times the return pulse to
+   *                    determine the range.
+   * @param units       The units returned in either kInches or kMilliMeters
+   */
+  Ultrasonic(std::shared_ptr<DigitalOutput> pingChannel,
+             std::shared_ptr<DigitalInput> echoChannel,
+             DistanceUnit units = kInches);
+
+  ~Ultrasonic() override;
+
+  Ultrasonic(Ultrasonic&&) = default;
+  Ultrasonic& operator=(Ultrasonic&&) = default;
+
+  /**
+   * Single ping to ultrasonic sensor.
+   *
+   * Send out a single ping to the ultrasonic sensor. This only works if
+   * automatic (round robin) mode is disabled. A single ping is sent out, and
+   * the counter should count the semi-period when it comes in. The counter is
+   * reset to make the current value invalid.
+   */
+  void Ping();
+
+  /**
+   * Check if there is a valid range measurement.
+   *
+   * The ranges are accumulated in a counter that will increment on each edge of
+   * the echo (return) signal. If the count is not at least 2, then the range
+   * has not yet been measured, and is invalid.
+   */
+  bool IsRangeValid() const;
+
+  /**
+   * Turn Automatic mode on/off.
+   *
+   * When in Automatic mode, all sensors will fire in round robin, waiting a set
+   * time between each sensor.
+   *
+   * @param enabling Set to true if round robin scheduling should start for all
+   *                 the ultrasonic sensors. This scheduling method assures that
+   *                 the sensors are non-interfering because no two sensors fire
+   *                 at the same time. If another scheduling algorithm is
+   *                 prefered, it can be implemented by pinging the sensors
+   *                 manually and waiting for the results to come back.
+   */
+  static void SetAutomaticMode(bool enabling);
+
+  /**
+   * Get the range in inches from the ultrasonic sensor.
+   *
+   * @return Range in inches of the target returned from the ultrasonic sensor.
+   *         If there is no valid value yet, i.e. at least one measurement
+   *         hasn't completed, then return 0.
+   */
+  double GetRangeInches() const;
+
+  /**
+   * Get the range in millimeters from the ultrasonic sensor.
+   *
+   * @return Range in millimeters of the target returned by the ultrasonic
+   *         sensor. If there is no valid value yet, i.e. at least one
+   *         measurement hasn't completed, then return 0.
+   */
+  double GetRangeMM() const;
+
+  bool IsEnabled() const;
+
+  void SetEnabled(bool enable);
+
+  /**
+   * Set the current DistanceUnit that should be used for the PIDSource base
+   * object.
+   *
+   * @param units The DistanceUnit that should be used.
+   */
+  void SetDistanceUnits(DistanceUnit units);
+
+  /**
+   * Get the current DistanceUnit that is used for the PIDSource base object.
+   *
+   * @return The type of DistanceUnit that is being used.
+   */
+  DistanceUnit GetDistanceUnits() const;
+
+  /**
+   * Get the range in the current DistanceUnit for the PIDSource base object.
+   *
+   * @return The range in DistanceUnit
+   */
+  double PIDGet() override;
+
+  void SetPIDSourceType(PIDSourceType pidSource) override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  /**
+   * Initialize the Ultrasonic Sensor.
+   *
+   * This is the common code that initializes the ultrasonic sensor given that
+   * there are two digital I/O channels allocated. If the system was running in
+   * automatic mode (round robin) when the new sensor is added, it is stopped,
+   * the sensor is added, then automatic mode is restored.
+   */
+  void Initialize();
+
+  /**
+   * Background task that goes through the list of ultrasonic sensors and pings
+   * each one in turn. The counter is configured to read the timing of the
+   * returned echo pulse.
+   *
+   * DANGER WILL ROBINSON, DANGER WILL ROBINSON:
+   * This code runs as a task and assumes that none of the ultrasonic sensors
+   * will change while it's running. Make sure to disable automatic mode before
+   * touching the list.
+   */
+  static void UltrasonicChecker();
+
+  // Time (sec) for the ping trigger pulse.
+  static constexpr double kPingTime = 10 * 1e-6;
+
+  // Priority that the ultrasonic round robin task runs.
+  static constexpr int kPriority = 64;
+
+  // Max time (ms) between readings.
+  static constexpr double kMaxUltrasonicTime = 0.1;
+  static constexpr double kSpeedOfSoundInchesPerSec = 1130.0 * 12.0;
+
+  // Thread doing the round-robin automatic sensing
+  static std::thread m_thread;
+
+  // Ultrasonic sensors
+  static std::vector<Ultrasonic*> m_sensors;
+
+  // Automatic round-robin mode
+  static std::atomic<bool> m_automaticEnabled;
+
+  std::shared_ptr<DigitalOutput> m_pingChannel;
+  std::shared_ptr<DigitalInput> m_echoChannel;
+  bool m_enabled = false;
+  Counter m_counter;
+  DistanceUnit m_units;
+
+  hal::SimDevice m_simDevice;
+  hal::SimBoolean m_simRangeValid;
+  hal::SimDouble m_simRange;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/Utility.h b/wpilibc/src/main/native/include/frc/Utility.h
new file mode 100644
index 0000000..3caaf84
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Utility.h
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/**
+ * @file Contains global utility functions
+ */
+
+#include <stdint.h>
+
+#include <string>
+
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/deprecated.h>
+
+#define wpi_assert(condition) \
+  wpi_assert_impl(condition, #condition, "", __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertWithMessage(condition, message)                     \
+  wpi_assert_impl(condition, #condition, message, __FILE__, __LINE__, \
+                  __FUNCTION__)
+
+#define wpi_assertEqual(a, b) \
+  wpi_assertEqual_impl(a, b, #a, #b, "", __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertEqualWithMessage(a, b, message) \
+  wpi_assertEqual_impl(a, b, #a, #b, message, __FILE__, __LINE__, __FUNCTION__)
+
+#define wpi_assertNotEqual(a, b) \
+  wpi_assertNotEqual_impl(a, b, #a, #b, "", __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertNotEqualWithMessage(a, b, message)                 \
+  wpi_assertNotEqual_impl(a, b, #a, #b, message, __FILE__, __LINE__, \
+                          __FUNCTION__)
+
+/**
+ * Assert implementation.
+ *
+ * This allows breakpoints to be set on an assert. The users don't call this,
+ * but instead use the wpi_assert macros in Utility.h.
+ */
+bool wpi_assert_impl(bool conditionValue, const wpi::Twine& conditionText,
+                     const wpi::Twine& message, wpi::StringRef fileName,
+                     int lineNumber, wpi::StringRef funcName);
+
+/**
+ * Assert equal implementation.
+ *
+ * This determines whether the two given integers are equal. If not, the value
+ * of each is printed along with an optional message string. The users don't
+ * call this, but instead use the wpi_assertEqual macros in Utility.h.
+ */
+bool wpi_assertEqual_impl(int valueA, int valueB,
+                          const wpi::Twine& valueAString,
+                          const wpi::Twine& valueBString,
+                          const wpi::Twine& message, wpi::StringRef fileName,
+                          int lineNumber, wpi::StringRef funcName);
+
+/**
+ * Assert not equal implementation.
+ *
+ * This determines whether the two given integers are equal. If so, the value of
+ * each is printed along with an optional message string. The users don't call
+ * this, but instead use the wpi_assertNotEqual macros in Utility.h.
+ */
+bool wpi_assertNotEqual_impl(int valueA, int valueB,
+                             const wpi::Twine& valueAString,
+                             const wpi::Twine& valueBString,
+                             const wpi::Twine& message, wpi::StringRef fileName,
+                             int lineNumber, wpi::StringRef funcName);
diff --git a/wpilibc/src/main/native/include/frc/Victor.h b/wpilibc/src/main/native/include/frc/Victor.h
new file mode 100644
index 0000000..89c4a89
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Victor.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Vex Robotics Victor 888 Speed Controller.
+ *
+ * The Vex Robotics Victor 884 Speed Controller can also be used with this
+ * class but may need to be calibrated per the Victor 884 user manual.
+ *
+ * Note that the Victor uses the following bounds for PWM values.  These
+ * values were determined empirically and optimized for the Victor 888. These
+ * values should work reasonably well for Victor 884 controllers as well but
+ * if users experience issues such as asymmetric behavior around the deadband
+ * or inability to saturate the controller in either direction, calibration is
+ * recommended. The calibration procedure can be found in the Victor 884 User
+ * Manual available from Vex.
+ *
+ * \li 2.027ms = full "forward"
+ * \li 1.525ms = the "high end" of the deadband range
+ * \li 1.507ms = center of the deadband range (off)
+ * \li 1.490ms = the "low end" of the deadband range
+ * \li 1.026ms = full "reverse"
+ */
+class Victor : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a Victor.
+   *
+   * @param channel The PWM channel number that the Victor is attached to. 0-9
+   *                are on-board, 10-19 are on the MXP port
+   */
+  explicit Victor(int channel);
+
+  Victor(Victor&&) = default;
+  Victor& operator=(Victor&&) = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/VictorSP.h b/wpilibc/src/main/native/include/frc/VictorSP.h
new file mode 100644
index 0000000..d8aa8e8
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/VictorSP.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Vex Robotics Victor SP Speed Controller.
+ *
+ * Note that the Victor SP uses the following bounds for PWM values. These
+ * values should work reasonably well for most controllers, but if users
+ * experience issues such as asymmetric behavior around the deadband or
+ * inability to saturate the controller in either direction, calibration is
+ * recommended. The calibration procedure can be found in the Victor SP User
+ * Manual available from Vex.
+ *
+ * \li 2.004ms = full "forward"
+ * \li 1.520ms = the "high end" of the deadband range
+ * \li 1.500ms = center of the deadband range (off)
+ * \li 1.480ms = the "low end" of the deadband range
+ * \li 0.997ms = full "reverse"
+ */
+class VictorSP : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a Victor SP.
+   *
+   * @param channel The PWM channel that the VictorSP is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit VictorSP(int channel);
+
+  VictorSP(VictorSP&&) = default;
+  VictorSP& operator=(VictorSP&&) = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/WPIErrors.h b/wpilibc/src/main/native/include/frc/WPIErrors.h
new file mode 100644
index 0000000..8325c92
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/WPIErrors.h
@@ -0,0 +1,95 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared 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>
+
+#define S(label, offset, message)                                        \
+  constexpr inline const char* wpi_error_s_##label() { return message; } \
+  constexpr inline int wpi_error_value_##label() { return offset; }
+
+// Fatal errors
+S(ModuleIndexOutOfRange, -1,
+  "Allocating module that is out of range or not found")
+S(ChannelIndexOutOfRange, -1, "Allocating channel that is out of range")
+S(NotAllocated, -2, "Attempting to free unallocated resource")
+S(ResourceAlreadyAllocated, -3, "Attempted to reuse an allocated resource")
+S(NoAvailableResources, -4, "No available resources to allocate")
+S(NullParameter, -5, "A pointer parameter to a method is nullptr")
+S(Timeout, -6, "A timeout has been exceeded")
+S(CompassManufacturerError, -7, "Compass manufacturer doesn't match HiTechnic")
+S(CompassTypeError, -8,
+  "Compass type doesn't match expected type for HiTechnic compass")
+S(IncompatibleMode, -9, "The object is in an incompatible mode")
+S(AnalogTriggerLimitOrderError, -10,
+  "AnalogTrigger limits error.  Lower limit > Upper Limit")
+S(AnalogTriggerPulseOutputError, -11,
+  "Attempted to read AnalogTrigger pulse output.")
+S(TaskError, -12, "Task can't be started")
+S(TaskIDError, -13, "Task error: Invalid ID.")
+S(TaskDeletedError, -14, "Task error: Task already deleted.")
+S(TaskOptionsError, -15, "Task error: Invalid options.")
+S(TaskMemoryError, -16, "Task can't be started due to insufficient memory.")
+S(TaskPriorityError, -17, "Task error: Invalid priority [1-255].")
+S(DriveUninitialized, -18, "RobotDrive not initialized for the C interface")
+S(CompressorNonMatching, -19,
+  "Compressor slot/channel doesn't match previous instance")
+S(CompressorAlreadyDefined, -20, "Creating a second compressor instance")
+S(CompressorUndefined, -21,
+  "Using compressor functions without defining compressor")
+S(InconsistentArrayValueAdded, -22,
+  "When packing data into an array to the dashboard, not all values added were "
+  "of the same type.")
+S(MismatchedComplexTypeClose, -23,
+  "When packing data to the dashboard, a Close for a complex type was called "
+  "without a matching Open.")
+S(DashboardDataOverflow, -24,
+  "When packing data to the dashboard, too much data was packed and the buffer "
+  "overflowed.")
+S(DashboardDataCollision, -25,
+  "The same buffer was used for packing data and for printing.")
+S(EnhancedIOMissing, -26, "IO is not attached or Enhanced IO is not enabled.")
+S(LineNotOutput, -27,
+  "Cannot SetDigitalOutput for a line not configured for output.")
+S(ParameterOutOfRange, -28, "A parameter is out of range.")
+S(SPIClockRateTooLow, -29, "SPI clock rate was below the minimum supported")
+S(JaguarVersionError, -30, "Jaguar firmware version error")
+S(JaguarMessageNotFound, -31, "Jaguar message not found")
+S(NetworkTablesReadError, -40, "Error reading NetworkTables socket")
+S(NetworkTablesBufferFull, -41, "Buffer full writing to NetworkTables socket")
+S(NetworkTablesWrongType, -42,
+  "The wrong type was read from the NetworkTables entry")
+S(NetworkTablesCorrupt, -43, "NetworkTables data stream is corrupt")
+S(SmartDashboardMissingKey, -43, "SmartDashboard data does not exist")
+S(CommandIllegalUse, -50, "Illegal use of Command")
+S(UnsupportedInSimulation, -80, "Unsupported in simulation")
+S(CameraServerError, -90, "CameraServer error")
+S(InvalidParameter, -100, "Invalid parameter value")
+
+// Warnings
+S(SampleRateTooHigh, 1, "Analog module sample rate is too high")
+S(VoltageOutOfRange, 2,
+  "Voltage to convert to raw value is out of range [-10; 10]")
+S(CompressorTaskError, 3, "Compressor task won't start")
+S(LoopTimingError, 4, "Digital module loop timing is not the expected value")
+S(NonBinaryDigitalValue, 5, "Digital output value is not 0 or 1")
+S(IncorrectBatteryChannel, 6,
+  "Battery measurement channel is not correct value")
+S(BadJoystickIndex, 7, "Joystick index is out of range, should be 0-3")
+S(BadJoystickAxis, 8, "Joystick axis or POV is out of range")
+S(InvalidMotorIndex, 9, "Motor index is out of range, should be 0-3")
+S(DriverStationTaskError, 10, "Driver Station task won't start")
+S(EnhancedIOPWMPeriodOutOfRange, 11,
+  "Driver Station Enhanced IO PWM Output period out of range.")
+S(SPIWriteNoMOSI, 12, "Cannot write to SPI port with no MOSI output")
+S(SPIReadNoMISO, 13, "Cannot read from SPI port with no MISO input")
+S(SPIReadNoData, 14, "No data available to read from SPI")
+S(IncompatibleState, 15,
+  "Incompatible State: The operation cannot be completed")
+
+#undef S
diff --git a/wpilibc/src/main/native/include/frc/WPILib.h b/wpilibc/src/main/native/include/frc/WPILib.h
new file mode 100644
index 0000000..9d62514
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/WPILib.h
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Including this header drastically increases compilation times and is bad style. Include only what you use instead."
+#else
+#warning "Including this header drastically increases compilation times and is bad style. Include only what you use instead."
+#endif
+
+// clang-format on
+
+#if __has_include(<cameraserver/CameraServer.h>)
+#include <cameraserver/CameraServer.h>
+#include <vision/VisionRunner.h>
+#endif
+
+#include "frc/ADXL345_I2C.h"
+#include "frc/ADXL345_SPI.h"
+#include "frc/ADXL362.h"
+#include "frc/ADXRS450_Gyro.h"
+#include "frc/AnalogAccelerometer.h"
+#include "frc/AnalogGyro.h"
+#include "frc/AnalogInput.h"
+#include "frc/AnalogOutput.h"
+#include "frc/AnalogPotentiometer.h"
+#include "frc/AnalogTrigger.h"
+#include "frc/AnalogTriggerOutput.h"
+#include "frc/BuiltInAccelerometer.h"
+#include "frc/Compressor.h"
+#include "frc/Counter.h"
+#include "frc/DMC60.h"
+#include "frc/DigitalInput.h"
+#include "frc/DigitalOutput.h"
+#include "frc/DigitalSource.h"
+#include "frc/DoubleSolenoid.h"
+#include "frc/DriverStation.h"
+#include "frc/Encoder.h"
+#include "frc/ErrorBase.h"
+#include "frc/GearTooth.h"
+#include "frc/GenericHID.h"
+#include "frc/I2C.h"
+#include "frc/InterruptableSensorBase.h"
+#include "frc/IterativeRobot.h"
+#include "frc/Jaguar.h"
+#include "frc/Joystick.h"
+#include "frc/NidecBrushless.h"
+#include "frc/Notifier.h"
+#include "frc/PIDController.h"
+#include "frc/PIDOutput.h"
+#include "frc/PIDSource.h"
+#include "frc/PWM.h"
+#include "frc/PWMSpeedController.h"
+#include "frc/PWMTalonSRX.h"
+#include "frc/PWMVictorSPX.h"
+#include "frc/PowerDistributionPanel.h"
+#include "frc/Preferences.h"
+#include "frc/Relay.h"
+#include "frc/RobotBase.h"
+#include "frc/RobotController.h"
+#include "frc/RobotDrive.h"
+#include "frc/SD540.h"
+#include "frc/SPI.h"
+#include "frc/SensorUtil.h"
+#include "frc/SerialPort.h"
+#include "frc/Servo.h"
+#include "frc/Solenoid.h"
+#include "frc/Spark.h"
+#include "frc/SpeedController.h"
+#include "frc/SpeedControllerGroup.h"
+#include "frc/Talon.h"
+#include "frc/Threads.h"
+#include "frc/TimedRobot.h"
+#include "frc/Timer.h"
+#include "frc/Ultrasonic.h"
+#include "frc/Utility.h"
+#include "frc/Victor.h"
+#include "frc/VictorSP.h"
+#include "frc/WPIErrors.h"
+#include "frc/XboxController.h"
+#if __has_include("frc/buttons/InternalButton.h")
+#include "frc/buttons/InternalButton.h"
+#include "frc/buttons/JoystickButton.h"
+#include "frc/buttons/NetworkButton.h"
+#include "frc/commands/Command.h"
+#include "frc/commands/CommandGroup.h"
+#include "frc/commands/PIDCommand.h"
+#include "frc/commands/PIDSubsystem.h"
+#include "frc/commands/PrintCommand.h"
+#include "frc/commands/StartCommand.h"
+#include "frc/commands/Subsystem.h"
+#include "frc/commands/WaitCommand.h"
+#include "frc/commands/WaitForChildren.h"
+#include "frc/commands/WaitUntilCommand.h"
+#endif
+#include "frc/drive/DifferentialDrive.h"
+#include "frc/drive/KilloughDrive.h"
+#include "frc/drive/MecanumDrive.h"
+#include "frc/filters/LinearDigitalFilter.h"
+#include "frc/interfaces/Accelerometer.h"
+#include "frc/interfaces/Gyro.h"
+#include "frc/interfaces/Potentiometer.h"
+#include "frc/smartdashboard/SendableChooser.h"
+#include "frc/smartdashboard/SmartDashboard.h"
diff --git a/wpilibc/src/main/native/include/frc/Watchdog.h b/wpilibc/src/main/native/include/frc/Watchdog.h
new file mode 100644
index 0000000..b36cf23
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/Watchdog.h
@@ -0,0 +1,167 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <chrono>
+#include <functional>
+#include <utility>
+
+#include <hal/cpp/fpga_clock.h>
+#include <units/units.h>
+#include <wpi/SafeThread.h>
+#include <wpi/StringMap.h>
+#include <wpi/StringRef.h>
+#include <wpi/deprecated.h>
+
+namespace frc {
+
+/**
+ * A class that's a wrapper around a watchdog timer.
+ *
+ * When the timer expires, a message is printed to the console and an optional
+ * user-provided callback is invoked.
+ *
+ * The watchdog is initialized disabled, so the user needs to call Enable()
+ * before use.
+ */
+class Watchdog {
+ public:
+  /**
+   * Watchdog constructor.
+   *
+   * @param timeout  The watchdog's timeout in seconds with microsecond
+   *                 resolution.
+   * @param callback This function is called when the timeout expires.
+   */
+  WPI_DEPRECATED("Use unit-safe version instead")
+  Watchdog(double timeout, std::function<void()> callback);
+
+  /**
+   * Watchdog constructor.
+   *
+   * @param timeout  The watchdog's timeout in seconds with microsecond
+   *                 resolution.
+   * @param callback This function is called when the timeout expires.
+   */
+  Watchdog(units::second_t timeout, std::function<void()> callback);
+
+  template <typename Callable, typename Arg, typename... Args>
+  WPI_DEPRECATED("Use unit-safe version instead")
+  Watchdog(double timeout, Callable&& f, Arg&& arg, Args&&... args)
+      : Watchdog(units::second_t{timeout}, arg, args...) {}
+
+  template <typename Callable, typename Arg, typename... Args>
+  Watchdog(units::second_t timeout, Callable&& f, Arg&& arg, Args&&... args)
+      : Watchdog(timeout,
+                 std::bind(std::forward<Callable>(f), std::forward<Arg>(arg),
+                           std::forward<Args>(args)...)) {}
+
+  ~Watchdog();
+
+  Watchdog(Watchdog&&) = default;
+  Watchdog& operator=(Watchdog&&) = default;
+
+  /**
+   * Returns the time in seconds since the watchdog was last fed.
+   */
+  double GetTime() const;
+
+  /**
+   * Sets the watchdog's timeout.
+   *
+   * @param timeout The watchdog's timeout in seconds with microsecond
+   *                resolution.
+   */
+  WPI_DEPRECATED("Use unit-safe version instead")
+  void SetTimeout(double timeout);
+
+  /**
+   * Sets the watchdog's timeout.
+   *
+   * @param timeout The watchdog's timeout in seconds with microsecond
+   *                resolution.
+   */
+  void SetTimeout(units::second_t timeout);
+
+  /**
+   * Returns the watchdog's timeout in seconds.
+   */
+  double GetTimeout() const;
+
+  /**
+   * Returns true if the watchdog timer has expired.
+   */
+  bool IsExpired() const;
+
+  /**
+   * Adds time since last epoch to the list printed by PrintEpochs().
+   *
+   * Epochs are a way to partition the time elapsed so that when overruns occur,
+   * one can determine which parts of an operation consumed the most time.
+   *
+   * @param epochName The name to associate with the epoch.
+   */
+  void AddEpoch(wpi::StringRef epochName);
+
+  /**
+   * Prints list of epochs added so far and their times.
+   */
+  void PrintEpochs();
+
+  /**
+   * Resets the watchdog timer.
+   *
+   * This also enables the timer if it was previously disabled.
+   */
+  void Reset();
+
+  /**
+   * Enables the watchdog timer.
+   */
+  void Enable();
+
+  /**
+   * Disables the watchdog timer.
+   */
+  void Disable();
+
+  /**
+   * Enable or disable suppression of the generic timeout message.
+   *
+   * This may be desirable if the user-provided callback already prints a more
+   * specific message.
+   *
+   * @param suppress Whether to suppress generic timeout message.
+   */
+  void SuppressTimeoutMessage(bool suppress);
+
+ private:
+  // Used for timeout print rate-limiting
+  static constexpr std::chrono::milliseconds kMinPrintPeriod{1000};
+
+  hal::fpga_clock::time_point m_startTime;
+  std::chrono::nanoseconds m_timeout;
+  hal::fpga_clock::time_point m_expirationTime;
+  std::function<void()> m_callback;
+  hal::fpga_clock::time_point m_lastTimeoutPrintTime = hal::fpga_clock::epoch();
+  hal::fpga_clock::time_point m_lastEpochsPrintTime = hal::fpga_clock::epoch();
+
+  wpi::StringMap<std::chrono::nanoseconds> m_epochs;
+  bool m_isExpired = false;
+
+  bool m_suppressTimeoutMessage = false;
+
+  class Thread;
+  wpi::SafeThreadOwner<Thread>* m_owner;
+
+  bool operator>(const Watchdog& rhs);
+
+  static wpi::SafeThreadOwner<Thread>& GetThreadOwner();
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/XboxController.h b/wpilibc/src/main/native/include/frc/XboxController.h
new file mode 100644
index 0000000..3ca2f4b
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/XboxController.h
@@ -0,0 +1,249 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/GenericHID.h"
+
+namespace frc {
+
+/**
+ * Handle input from Xbox 360 or Xbox One controllers connected to the Driver
+ * Station.
+ *
+ * This class handles Xbox input that comes from the Driver Station. Each time a
+ * value is requested the most recent value is returned. There is a single class
+ * instance for each controller and the mapping of ports to hardware buttons
+ * depends on the code in the Driver Station.
+ */
+class XboxController : public GenericHID {
+ public:
+  /**
+   * Construct an instance of an Xbox controller.
+   *
+   * The controller index is the USB port on the Driver Station.
+   *
+   * @param port The port on the Driver Station that the controller is plugged
+   *             into (0-5).
+   */
+  explicit XboxController(int port);
+
+  virtual ~XboxController() = default;
+
+  XboxController(XboxController&&) = default;
+  XboxController& operator=(XboxController&&) = default;
+
+  /**
+   * Get the X axis value of the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   */
+  double GetX(JoystickHand hand) const override;
+
+  /**
+   * Get the Y axis value of the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   */
+  double GetY(JoystickHand hand) const override;
+
+  /**
+   * Get the trigger axis value of the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   */
+  double GetTriggerAxis(JoystickHand hand) const;
+
+  /**
+   * Read the value of the bumper button on the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   */
+  bool GetBumper(JoystickHand hand) const;
+
+  /**
+   * Whether the bumper was pressed since the last check.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetBumperPressed(JoystickHand hand);
+
+  /**
+   * Whether the bumper was released since the last check.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return Whether the button was released since the last check.
+   */
+  bool GetBumperReleased(JoystickHand hand);
+
+  /**
+   * Read the value of the stick button on the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return The state of the button.
+   */
+  bool GetStickButton(JoystickHand hand) const;
+
+  /**
+   * Whether the stick button was pressed since the last check.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetStickButtonPressed(JoystickHand hand);
+
+  /**
+   * Whether the stick button was released since the last check.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return Whether the button was released since the last check.
+   */
+  bool GetStickButtonReleased(JoystickHand hand);
+
+  /**
+   * Read the value of the A button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetAButton() const;
+
+  /**
+   * Whether the A button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetAButtonPressed();
+
+  /**
+   * Whether the A button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetAButtonReleased();
+
+  /**
+   * Read the value of the B button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetBButton() const;
+
+  /**
+   * Whether the B button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetBButtonPressed();
+
+  /**
+   * Whether the B button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetBButtonReleased();
+
+  /**
+   * Read the value of the X button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetXButton() const;
+
+  /**
+   * Whether the X button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetXButtonPressed();
+
+  /**
+   * Whether the X button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetXButtonReleased();
+
+  /**
+   * Read the value of the Y button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetYButton() const;
+
+  /**
+   * Whether the Y button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetYButtonPressed();
+
+  /**
+   * Whether the Y button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetYButtonReleased();
+
+  /**
+   * Whether the Y button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetBackButton() const;
+
+  /**
+   * Whether the back button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetBackButtonPressed();
+
+  /**
+   * Whether the back button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetBackButtonReleased();
+
+  /**
+   * Read the value of the start button on the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return The state of the button.
+   */
+  bool GetStartButton() const;
+
+  /**
+   * Whether the start button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetStartButtonPressed();
+
+  /**
+   * Whether the start button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetStartButtonReleased();
+
+  enum class Button {
+    kBumperLeft = 5,
+    kBumperRight = 6,
+    kStickLeft = 9,
+    kStickRight = 10,
+    kA = 1,
+    kB = 2,
+    kX = 3,
+    kY = 4,
+    kBack = 7,
+    kStart = 8
+  };
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/controller/ArmFeedforward.h b/wpilibc/src/main/native/include/frc/controller/ArmFeedforward.h
new file mode 100644
index 0000000..6f6e086
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/controller/ArmFeedforward.h
@@ -0,0 +1,149 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+#include <wpi/MathExtras.h>
+
+namespace frc {
+/**
+ * A helper class that computes feedforward outputs for a simple arm (modeled as
+ * a motor acting against the force of gravity on a beam suspended at an angle).
+ */
+class ArmFeedforward {
+  using Angle = units::radians;
+  using Velocity = units::radians_per_second;
+  using Acceleration = units::compound_unit<units::radians_per_second,
+                                            units::inverse<units::second>>;
+  using kv_unit =
+      units::compound_unit<units::volts,
+                           units::inverse<units::radians_per_second>>;
+  using ka_unit =
+      units::compound_unit<units::volts, units::inverse<Acceleration>>;
+
+ public:
+  constexpr ArmFeedforward() = default;
+
+  /**
+   * Creates a new ArmFeedforward with the specified gains.
+   *
+   * @param kS   The static gain, in volts.
+   * @param kCos The gravity gain, in volts.
+   * @param kV   The velocity gain, in volt seconds per radian.
+   * @param kA   The acceleration gain, in volt seconds^2 per radian.
+   */
+  constexpr ArmFeedforward(
+      units::volt_t kS, units::volt_t kCos, units::unit_t<kv_unit> kV,
+      units::unit_t<ka_unit> kA = units::unit_t<ka_unit>(0))
+      : kS(kS), kCos(kCos), kV(kV), kA(kA) {}
+
+  /**
+   * Calculates the feedforward from the gains and setpoints.
+   *
+   * @param angle        The angle setpoint, in radians.
+   * @param velocity     The velocity setpoint, in radians per second.
+   * @param acceleration The acceleration setpoint, in radians per second^2.
+   * @return The computed feedforward, in volts.
+   */
+  units::volt_t Calculate(units::unit_t<Angle> angle,
+                          units::unit_t<Velocity> velocity,
+                          units::unit_t<Acceleration> acceleration =
+                              units::unit_t<Acceleration>(0)) const {
+    return kS * wpi::sgn(velocity) + kCos * units::math::cos(angle) +
+           kV * velocity + kA * acceleration;
+  }
+
+  // Rearranging the main equation from the calculate() method yields the
+  // formulas for the methods below:
+
+  /**
+   * Calculates the maximum achievable velocity given a maximum voltage supply,
+   * a position, and an acceleration.  Useful for ensuring that velocity and
+   * acceleration constraints for a trapezoidal profile are simultaneously
+   * achievable - enter the acceleration constraint, and this will give you
+   * a simultaneously-achievable velocity constraint.
+   *
+   * @param maxVoltage The maximum voltage that can be supplied to the arm.
+   * @param angle The angle of the arm
+   * @param acceleration The acceleration of the arm.
+   * @return The maximum possible velocity at the given acceleration and angle.
+   */
+  units::unit_t<Velocity> MaxAchievableVelocity(
+      units::volt_t maxVoltage, units::unit_t<Angle> angle,
+      units::unit_t<Acceleration> acceleration) {
+    // Assume max velocity is positive
+    return (maxVoltage - kS - kCos * units::math::cos(angle) -
+            kA * acceleration) /
+           kV;
+  }
+
+  /**
+   * Calculates the minimum achievable velocity given a maximum voltage supply,
+   * a position, and an acceleration.  Useful for ensuring that velocity and
+   * acceleration constraints for a trapezoidal profile are simultaneously
+   * achievable - enter the acceleration constraint, and this will give you
+   * a simultaneously-achievable velocity constraint.
+   *
+   * @param maxVoltage The maximum voltage that can be supplied to the arm.
+   * @param angle The angle of the arm
+   * @param acceleration The acceleration of the arm.
+   * @return The minimum possible velocity at the given acceleration and angle.
+   */
+  units::unit_t<Velocity> MinAchievableVelocity(
+      units::volt_t maxVoltage, units::unit_t<Angle> angle,
+      units::unit_t<Acceleration> acceleration) {
+    // Assume min velocity is negative, ks flips sign
+    return (-maxVoltage + kS - kCos * units::math::cos(angle) -
+            kA * acceleration) /
+           kV;
+  }
+
+  /**
+   * Calculates the maximum achievable acceleration given a maximum voltage
+   * supply, a position, and a velocity. Useful for ensuring that velocity and
+   * acceleration constraints for a trapezoidal profile are simultaneously
+   * achievable - enter the velocity constraint, and this will give you
+   * a simultaneously-achievable acceleration constraint.
+   *
+   * @param maxVoltage The maximum voltage that can be supplied to the arm.
+   * @param angle The angle of the arm
+   * @param velocity The velocity of the arm.
+   * @return The maximum possible acceleration at the given velocity and angle.
+   */
+  units::unit_t<Acceleration> MaxAchievableAcceleration(
+      units::volt_t maxVoltage, units::unit_t<Angle> angle,
+      units::unit_t<Velocity> velocity) {
+    return (maxVoltage - kS * wpi::sgn(velocity) -
+            kCos * units::math::cos(angle) - kV * velocity) /
+           kA;
+  }
+
+  /**
+   * Calculates the minimum achievable acceleration given a maximum voltage
+   * supply, a position, and a velocity. Useful for ensuring that velocity and
+   * acceleration constraints for a trapezoidal profile are simultaneously
+   * achievable - enter the velocity constraint, and this will give you
+   * a simultaneously-achievable acceleration constraint.
+   *
+   * @param maxVoltage The maximum voltage that can be supplied to the arm.
+   * @param angle The angle of the arm
+   * @param velocity The velocity of the arm.
+   * @return The minimum possible acceleration at the given velocity and angle.
+   */
+  units::unit_t<Acceleration> MinAchievableAcceleration(
+      units::volt_t maxVoltage, units::unit_t<Angle> angle,
+      units::unit_t<Velocity> velocity) {
+    return MaxAchievableAcceleration(-maxVoltage, angle, velocity);
+  }
+
+  units::volt_t kS{0};
+  units::volt_t kCos{0};
+  units::unit_t<kv_unit> kV{0};
+  units::unit_t<ka_unit> kA{0};
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/controller/ElevatorFeedforward.h b/wpilibc/src/main/native/include/frc/controller/ElevatorFeedforward.h
new file mode 100644
index 0000000..c664fc4
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/controller/ElevatorFeedforward.h
@@ -0,0 +1,131 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+#include <wpi/MathExtras.h>
+
+namespace frc {
+/**
+ * A helper class that computes feedforward outputs for a simple elevator
+ * (modeled as a motor acting against the force of gravity).
+ */
+template <class Distance>
+class ElevatorFeedforward {
+  using Velocity =
+      units::compound_unit<Distance, units::inverse<units::seconds>>;
+  using Acceleration =
+      units::compound_unit<Velocity, units::inverse<units::seconds>>;
+  using kv_unit = units::compound_unit<units::volts, units::inverse<Velocity>>;
+  using ka_unit =
+      units::compound_unit<units::volts, units::inverse<Acceleration>>;
+
+ public:
+  ElevatorFeedforward() = default;
+
+  /**
+   * Creates a new ElevatorFeedforward with the specified gains.
+   *
+   * @param kS The static gain, in volts.
+   * @param kG The gravity gain, in volts.
+   * @param kV The velocity gain, in volt seconds per distance.
+   * @param kA The acceleration gain, in volt seconds^2 per distance.
+   */
+  constexpr ElevatorFeedforward(
+      units::volt_t kS, units::volt_t kG, units::unit_t<kv_unit> kV,
+      units::unit_t<ka_unit> kA = units::unit_t<ka_unit>(0))
+      : kS(kS), kG(kG), kV(kV), kA(kA) {}
+
+  /**
+   * Calculates the feedforward from the gains and setpoints.
+   *
+   * @param velocity     The velocity setpoint, in distance per second.
+   * @param acceleration The acceleration setpoint, in distance per second^2.
+   * @return The computed feedforward, in volts.
+   */
+  constexpr units::volt_t Calculate(units::unit_t<Velocity> velocity,
+                                    units::unit_t<Acceleration> acceleration =
+                                        units::unit_t<Acceleration>(0)) {
+    return kS * wpi::sgn(velocity) + kG + kV * velocity + kA * acceleration;
+  }
+
+  // Rearranging the main equation from the calculate() method yields the
+  // formulas for the methods below:
+
+  /**
+   * Calculates the maximum achievable velocity given a maximum voltage supply
+   * and an acceleration.  Useful for ensuring that velocity and
+   * acceleration constraints for a trapezoidal profile are simultaneously
+   * achievable - enter the acceleration constraint, and this will give you
+   * a simultaneously-achievable velocity constraint.
+   *
+   * @param maxVoltage The maximum voltage that can be supplied to the elevator.
+   * @param acceleration The acceleration of the elevator.
+   * @return The maximum possible velocity at the given acceleration.
+   */
+  constexpr units::unit_t<Velocity> MaxAchievableVelocity(
+      units::volt_t maxVoltage, units::unit_t<Acceleration> acceleration) {
+    // Assume max velocity is positive
+    return (maxVoltage - kS - kG - kA * acceleration) / kV;
+  }
+
+  /**
+   * Calculates the minimum achievable velocity given a maximum voltage supply
+   * and an acceleration.  Useful for ensuring that velocity and
+   * acceleration constraints for a trapezoidal profile are simultaneously
+   * achievable - enter the acceleration constraint, and this will give you
+   * a simultaneously-achievable velocity constraint.
+   *
+   * @param maxVoltage The maximum voltage that can be supplied to the elevator.
+   * @param acceleration The acceleration of the elevator.
+   * @return The minimum possible velocity at the given acceleration.
+   */
+  constexpr units::unit_t<Velocity> MinAchievableVelocity(
+      units::volt_t maxVoltage, units::unit_t<Acceleration> acceleration) {
+    // Assume min velocity is negative, ks flips sign
+    return (-maxVoltage + kS - kG - kA * acceleration) / kV;
+  }
+
+  /**
+   * Calculates the maximum achievable acceleration given a maximum voltage
+   * supply and a velocity. Useful for ensuring that velocity and
+   * acceleration constraints for a trapezoidal profile are simultaneously
+   * achievable - enter the velocity constraint, and this will give you
+   * a simultaneously-achievable acceleration constraint.
+   *
+   * @param maxVoltage The maximum voltage that can be supplied to the elevator.
+   * @param velocity The velocity of the elevator.
+   * @return The maximum possible acceleration at the given velocity.
+   */
+  constexpr units::unit_t<Acceleration> MaxAchievableAcceleration(
+      units::volt_t maxVoltage, units::unit_t<Velocity> velocity) {
+    return (maxVoltage - kS * wpi::sgn(velocity) - kG - kV * velocity) / kA;
+  }
+
+  /**
+   * Calculates the minimum achievable acceleration given a maximum voltage
+   * supply and a velocity. Useful for ensuring that velocity and
+   * acceleration constraints for a trapezoidal profile are simultaneously
+   * achievable - enter the velocity constraint, and this will give you
+   * a simultaneously-achievable acceleration constraint.
+   *
+   * @param maxVoltage The maximum voltage that can be supplied to the elevator.
+   * @param velocity The velocity of the elevator.
+   * @return The minimum possible acceleration at the given velocity.
+   */
+  constexpr units::unit_t<Acceleration> MinAchievableAcceleration(
+      units::volt_t maxVoltage, units::unit_t<Velocity> velocity) {
+    return MaxAchievableAcceleration(-maxVoltage, velocity);
+  }
+
+  units::volt_t kS{0};
+  units::volt_t kG{0};
+  units::unit_t<kv_unit> kV{0};
+  units::unit_t<ka_unit> kA{0};
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/controller/PIDController.h b/wpilibc/src/main/native/include/frc/controller/PIDController.h
new file mode 100644
index 0000000..66a36fb
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/controller/PIDController.h
@@ -0,0 +1,261 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+#include <limits>
+
+#include <units/units.h>
+
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc2 {
+
+/**
+ * Implements a PID control loop.
+ */
+class PIDController : public frc::Sendable,
+                      public frc::SendableHelper<PIDController> {
+ public:
+  /**
+   * Allocates a PIDController with the given constants for Kp, Ki, and Kd.
+   *
+   * @param Kp     The proportional coefficient.
+   * @param Ki     The integral coefficient.
+   * @param Kd     The derivative coefficient.
+   * @param period The period between controller updates in seconds. The
+   *               default is 20 milliseconds.
+   */
+  PIDController(double Kp, double Ki, double Kd,
+                units::second_t period = 20_ms);
+
+  ~PIDController() override = default;
+
+  PIDController(const PIDController&) = default;
+  PIDController& operator=(const PIDController&) = default;
+  PIDController(PIDController&&) = default;
+  PIDController& operator=(PIDController&&) = default;
+
+  /**
+   * Sets the PID Controller gain parameters.
+   *
+   * Sets the proportional, integral, and differential coefficients.
+   *
+   * @param Kp Proportional coefficient
+   * @param Ki Integral coefficient
+   * @param Kd Differential coefficient
+   */
+  void SetPID(double Kp, double Ki, double Kd);
+
+  /**
+   * Sets the proportional coefficient of the PID controller gain.
+   *
+   * @param Kp proportional coefficient
+   */
+  void SetP(double Kp);
+
+  /**
+   * Sets the integral coefficient of the PID controller gain.
+   *
+   * @param Ki integral coefficient
+   */
+  void SetI(double Ki);
+
+  /**
+   * Sets the differential coefficient of the PID controller gain.
+   *
+   * @param Kd differential coefficient
+   */
+  void SetD(double Kd);
+
+  /**
+   * Gets the proportional coefficient.
+   *
+   * @return proportional coefficient
+   */
+  double GetP() const;
+
+  /**
+   * Gets the integral coefficient.
+   *
+   * @return integral coefficient
+   */
+  double GetI() const;
+
+  /**
+   * Gets the differential coefficient.
+   *
+   * @return differential coefficient
+   */
+  double GetD() const;
+
+  /**
+   * Gets the period of this controller.
+   *
+   * @return The period of the controller.
+   */
+  units::second_t GetPeriod() const;
+
+  /**
+   * Sets the setpoint for the PIDController.
+   *
+   * @param setpoint The desired setpoint.
+   */
+  void SetSetpoint(double setpoint);
+
+  /**
+   * Returns the current setpoint of the PIDController.
+   *
+   * @return The current setpoint.
+   */
+  double GetSetpoint() const;
+
+  /**
+   * Returns true if the error is within the tolerance of the error.
+   *
+   * This will return false until at least one input value has been computed.
+   */
+  bool AtSetpoint() const;
+
+  /**
+   * Enables continuous input.
+   *
+   * Rather then using the max and min input range as constraints, it considers
+   * them to be the same point and automatically calculates the shortest route
+   * to the setpoint.
+   *
+   * @param minimumInput The minimum value expected from the input.
+   * @param maximumInput The maximum value expected from the input.
+   */
+  void EnableContinuousInput(double minimumInput, double maximumInput);
+
+  /**
+   * Disables continuous input.
+   */
+  void DisableContinuousInput();
+
+  /**
+   * Sets the minimum and maximum values for the integrator.
+   *
+   * When the cap is reached, the integrator value is added to the controller
+   * output rather than the integrator value times the integral gain.
+   *
+   * @param minimumIntegral The minimum value of the integrator.
+   * @param maximumIntegral The maximum value of the integrator.
+   */
+  void SetIntegratorRange(double minimumIntegral, double maximumIntegral);
+
+  /**
+   * Sets the error which is considered tolerable for use with AtSetpoint().
+   *
+   * @param positionTolerance Position error which is tolerable.
+   * @param velociytTolerance Velocity error which is tolerable.
+   */
+  void SetTolerance(
+      double positionTolerance,
+      double velocityTolerance = std::numeric_limits<double>::infinity());
+
+  /**
+   * Returns the difference between the setpoint and the measurement.
+   */
+  double GetPositionError() const;
+
+  /**
+   * Returns the velocity error.
+   */
+  double GetVelocityError() const;
+
+  /**
+   * Returns the next output of the PID controller.
+   *
+   * @param measurement The current measurement of the process variable.
+   */
+  double Calculate(double measurement);
+
+  /**
+   * Returns the next output of the PID controller.
+   *
+   * @param measurement The current measurement of the process variable.
+   * @param setpoint The new setpoint of the controller.
+   */
+  double Calculate(double measurement, double setpoint);
+
+  /**
+   * Reset the previous error, the integral term, and disable the controller.
+   */
+  void Reset();
+
+  void InitSendable(frc::SendableBuilder& builder) override;
+
+ protected:
+  /**
+   * Wraps error around for continuous inputs. The original error is returned if
+   * continuous mode is disabled.
+   *
+   * @param error The current error of the PID controller.
+   * @return Error for continuous inputs.
+   */
+  double GetContinuousError(double error) const;
+
+ private:
+  // Factor for "proportional" control
+  double m_Kp;
+
+  // Factor for "integral" control
+  double m_Ki;
+
+  // Factor for "derivative" control
+  double m_Kd;
+
+  // The period (in seconds) of the control loop running this controller
+  units::second_t m_period;
+
+  double m_maximumIntegral = 1.0;
+
+  double m_minimumIntegral = -1.0;
+
+  // Maximum input - limit setpoint to this
+  double m_maximumInput = 0;
+
+  // Minimum input - limit setpoint to this
+  double m_minimumInput = 0;
+
+  // Input range - difference between maximum and minimum
+  double m_inputRange = 0;
+
+  // Do the endpoints wrap around? eg. Absolute encoder
+  bool m_continuous = false;
+
+  // The error at the time of the most recent call to Calculate()
+  double m_positionError = 0;
+  double m_velocityError = 0;
+
+  // The error at the time of the second-most-recent call to Calculate() (used
+  // to compute velocity)
+  double m_prevError = 0;
+
+  // The sum of the errors for use in the integral calc
+  double m_totalError = 0;
+
+  // The error that is considered at setpoint.
+  double m_positionTolerance = 0.05;
+  double m_velocityTolerance = std::numeric_limits<double>::infinity();
+
+  double m_setpoint = 0;
+
+  /**
+   * Sets the minimum and maximum values expected from the input.
+   *
+   * @param minimumInput The minimum value expected from the input.
+   * @param maximumInput The maximum value expected from the input.
+   */
+  void SetInputRange(double minimumInput, double maximumInput);
+};
+
+}  // namespace frc2
diff --git a/wpilibc/src/main/native/include/frc/controller/ProfiledPIDController.h b/wpilibc/src/main/native/include/frc/controller/ProfiledPIDController.h
new file mode 100644
index 0000000..079d96e
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/controller/ProfiledPIDController.h
@@ -0,0 +1,345 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019-2020 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared 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 <cmath>
+#include <functional>
+#include <limits>
+
+#include <units/units.h>
+
+#include "frc/controller/PIDController.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableHelper.h"
+#include "frc/trajectory/TrapezoidProfile.h"
+
+namespace frc {
+namespace detail {
+void ReportProfiledPIDController();
+}  // namespace detail
+
+/**
+ * Implements a PID control loop whose setpoint is constrained by a trapezoid
+ * profile.
+ */
+template <class Distance>
+class ProfiledPIDController
+    : public Sendable,
+      public SendableHelper<ProfiledPIDController<Distance>> {
+  using Distance_t = units::unit_t<Distance>;
+  using Velocity =
+      units::compound_unit<Distance, units::inverse<units::seconds>>;
+  using Velocity_t = units::unit_t<Velocity>;
+  using Acceleration =
+      units::compound_unit<Velocity, units::inverse<units::seconds>>;
+  using Acceleration_t = units::unit_t<Acceleration>;
+  using State = typename TrapezoidProfile<Distance>::State;
+  using Constraints = typename TrapezoidProfile<Distance>::Constraints;
+
+ public:
+  /**
+   * Allocates a ProfiledPIDController with the given constants for Kp, Ki, and
+   * Kd. Users should call reset() when they first start running the controller
+   * to avoid unwanted behavior.
+   *
+   * @param Kp          The proportional coefficient.
+   * @param Ki          The integral coefficient.
+   * @param Kd          The derivative coefficient.
+   * @param constraints Velocity and acceleration constraints for goal.
+   * @param period      The period between controller updates in seconds. The
+   *                    default is 20 milliseconds.
+   */
+  ProfiledPIDController(double Kp, double Ki, double Kd,
+                        Constraints constraints, units::second_t period = 20_ms)
+      : m_controller(Kp, Ki, Kd, period), m_constraints(constraints) {
+    detail::ReportProfiledPIDController();
+  }
+
+  ~ProfiledPIDController() override = default;
+
+  ProfiledPIDController(const ProfiledPIDController&) = default;
+  ProfiledPIDController& operator=(const ProfiledPIDController&) = default;
+  ProfiledPIDController(ProfiledPIDController&&) = default;
+  ProfiledPIDController& operator=(ProfiledPIDController&&) = default;
+
+  /**
+   * Sets the PID Controller gain parameters.
+   *
+   * Sets the proportional, integral, and differential coefficients.
+   *
+   * @param Kp Proportional coefficient
+   * @param Ki Integral coefficient
+   * @param Kd Differential coefficient
+   */
+  void SetPID(double Kp, double Ki, double Kd) {
+    m_controller.SetPID(Kp, Ki, Kd);
+  }
+
+  /**
+   * Sets the proportional coefficient of the PID controller gain.
+   *
+   * @param Kp proportional coefficient
+   */
+  void SetP(double Kp) { m_controller.SetP(Kp); }
+
+  /**
+   * Sets the integral coefficient of the PID controller gain.
+   *
+   * @param Ki integral coefficient
+   */
+  void SetI(double Ki) { m_controller.SetI(Ki); }
+
+  /**
+   * Sets the differential coefficient of the PID controller gain.
+   *
+   * @param Kd differential coefficient
+   */
+  void SetD(double Kd) { m_controller.SetD(Kd); }
+
+  /**
+   * Gets the proportional coefficient.
+   *
+   * @return proportional coefficient
+   */
+  double GetP() const { return m_controller.GetP(); }
+
+  /**
+   * Gets the integral coefficient.
+   *
+   * @return integral coefficient
+   */
+  double GetI() const { return m_controller.GetI(); }
+
+  /**
+   * Gets the differential coefficient.
+   *
+   * @return differential coefficient
+   */
+  double GetD() const { return m_controller.GetD(); }
+
+  /**
+   * Gets the period of this controller.
+   *
+   * @return The period of the controller.
+   */
+  units::second_t GetPeriod() const { return m_controller.GetPeriod(); }
+
+  /**
+   * Sets the goal for the ProfiledPIDController.
+   *
+   * @param goal The desired unprofiled setpoint.
+   */
+  void SetGoal(State goal) { m_goal = goal; }
+
+  /**
+   * Sets the goal for the ProfiledPIDController.
+   *
+   * @param goal The desired unprofiled setpoint.
+   */
+  void SetGoal(Distance_t goal) { m_goal = {goal, Velocity_t(0)}; }
+
+  /**
+   * Gets the goal for the ProfiledPIDController.
+   */
+  State GetGoal() const { return m_goal; }
+
+  /**
+   * Returns true if the error is within the tolerance of the error.
+   *
+   * This will return false until at least one input value has been computed.
+   */
+  bool AtGoal() const { return AtSetpoint() && m_goal == m_setpoint; }
+
+  /**
+   * Set velocity and acceleration constraints for goal.
+   *
+   * @param constraints Velocity and acceleration constraints for goal.
+   */
+  void SetConstraints(Constraints constraints) { m_constraints = constraints; }
+
+  /**
+   * Returns the current setpoint of the ProfiledPIDController.
+   *
+   * @return The current setpoint.
+   */
+  State GetSetpoint() const { return m_setpoint; }
+
+  /**
+   * Returns true if the error is within the tolerance of the error.
+   *
+   * Currently this just reports on target as the actual value passes through
+   * the setpoint. Ideally it should be based on being within the tolerance for
+   * some period of time.
+   *
+   * This will return false until at least one input value has been computed.
+   */
+  bool AtSetpoint() const { return m_controller.AtSetpoint(); }
+
+  /**
+   * Enables continuous input.
+   *
+   * Rather then using the max and min input range as constraints, it considers
+   * them to be the same point and automatically calculates the shortest route
+   * to the setpoint.
+   *
+   * @param minimumInput The minimum value expected from the input.
+   * @param maximumInput The maximum value expected from the input.
+   */
+  void EnableContinuousInput(Distance_t minimumInput, Distance_t maximumInput) {
+    m_controller.EnableContinuousInput(minimumInput.template to<double>(),
+                                       maximumInput.template to<double>());
+  }
+
+  /**
+   * Disables continuous input.
+   */
+  void DisableContinuousInput() { m_controller.DisableContinuousInput(); }
+
+  /**
+   * Sets the minimum and maximum values for the integrator.
+   *
+   * When the cap is reached, the integrator value is added to the controller
+   * output rather than the integrator value times the integral gain.
+   *
+   * @param minimumIntegral The minimum value of the integrator.
+   * @param maximumIntegral The maximum value of the integrator.
+   */
+  void SetIntegratorRange(double minimumIntegral, double maximumIntegral) {
+    m_controller.SetIntegratorRange(minimumIntegral, maximumIntegral);
+  }
+
+  /**
+   * Sets the error which is considered tolerable for use with
+   * AtSetpoint().
+   *
+   * @param positionTolerance Position error which is tolerable.
+   * @param velocityTolerance Velocity error which is tolerable.
+   */
+  void SetTolerance(
+      Distance_t positionTolerance,
+      Velocity_t velocityTolerance = std::numeric_limits<double>::infinity()) {
+    m_controller.SetTolerance(positionTolerance.template to<double>(),
+                              velocityTolerance.template to<double>());
+  }
+
+  /**
+   * Returns the difference between the setpoint and the measurement.
+   *
+   * @return The error.
+   */
+  Distance_t GetPositionError() const {
+    return Distance_t(m_controller.GetPositionError());
+  }
+
+  /**
+   * Returns the change in error per second.
+   */
+  Velocity_t GetVelocityError() const {
+    return Velocity_t(m_controller.GetVelocityError());
+  }
+
+  /**
+   * Returns the next output of the PID controller.
+   *
+   * @param measurement The current measurement of the process variable.
+   */
+  double Calculate(Distance_t measurement) {
+    frc::TrapezoidProfile<Distance> profile{m_constraints, m_goal, m_setpoint};
+    m_setpoint = profile.Calculate(GetPeriod());
+    return m_controller.Calculate(measurement.template to<double>(),
+                                  m_setpoint.position.template to<double>());
+  }
+
+  /**
+   * Returns the next output of the PID controller.
+   *
+   * @param measurement The current measurement of the process variable.
+   * @param goal The new goal of the controller.
+   */
+  double Calculate(Distance_t measurement, State goal) {
+    SetGoal(goal);
+    return Calculate(measurement);
+  }
+  /**
+   * Returns the next output of the PID controller.
+   *
+   * @param measurement The current measurement of the process variable.
+   * @param goal The new goal of the controller.
+   */
+  double Calculate(Distance_t measurement, Distance_t goal) {
+    SetGoal(goal);
+    return Calculate(measurement);
+  }
+
+  /**
+   * Returns the next output of the PID controller.
+   *
+   * @param measurement The current measurement of the process variable.
+   * @param goal        The new goal of the controller.
+   * @param constraints Velocity and acceleration constraints for goal.
+   */
+  double Calculate(
+      Distance_t measurement, Distance_t goal,
+      typename frc::TrapezoidProfile<Distance>::Constraints constraints) {
+    SetConstraints(constraints);
+    return Calculate(measurement, goal);
+  }
+
+  /**
+   * Reset the previous error and the integral term.
+   *
+   * @param measurement The current measured State of the system.
+   */
+  void Reset(const State& measurement) {
+    m_controller.Reset();
+    m_setpoint = measurement;
+  }
+
+  /**
+   * Reset the previous error and the integral term.
+   *
+   * @param measuredPosition The current measured position of the system.
+   * @param measuredVelocity The current measured velocity of the system.
+   */
+  void Reset(Distance_t measuredPosition, Velocity_t measuredVelocity) {
+    Reset(State{measuredPosition, measuredVelocity});
+  }
+
+  /**
+   * Reset the previous error and the integral term.
+   *
+   * @param measuredPosition The current measured position of the system. The
+   * velocity is assumed to be zero.
+   */
+  void Reset(Distance_t measuredPosition) {
+    Reset(measuredPosition, Velocity_t(0));
+  }
+
+  void InitSendable(frc::SendableBuilder& builder) override {
+    builder.SetSmartDashboardType("ProfiledPIDController");
+    builder.AddDoubleProperty("p", [this] { return GetP(); },
+                              [this](double value) { SetP(value); });
+    builder.AddDoubleProperty("i", [this] { return GetI(); },
+                              [this](double value) { SetI(value); });
+    builder.AddDoubleProperty("d", [this] { return GetD(); },
+                              [this](double value) { SetD(value); });
+    builder.AddDoubleProperty(
+        "goal", [this] { return GetGoal().position.template to<double>(); },
+        [this](double value) { SetGoal(Distance_t{value}); });
+  }
+
+ private:
+  frc2::PIDController m_controller;
+  typename frc::TrapezoidProfile<Distance>::State m_goal;
+  typename frc::TrapezoidProfile<Distance>::State m_setpoint;
+  typename frc::TrapezoidProfile<Distance>::Constraints m_constraints;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/controller/RamseteController.h b/wpilibc/src/main/native/include/frc/controller/RamseteController.h
new file mode 100644
index 0000000..6ec6edc
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/controller/RamseteController.h
@@ -0,0 +1,113 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+
+#include "frc/geometry/Pose2d.h"
+#include "frc/kinematics/ChassisSpeeds.h"
+#include "frc/trajectory/Trajectory.h"
+
+namespace frc {
+
+/**
+ * Ramsete is a nonlinear time-varying feedback controller for unicycle models
+ * that drives the model to a desired pose along a two-dimensional trajectory.
+ * Why would we need a nonlinear control law in addition to the linear ones we
+ * have used so far like PID? If we use the original approach with PID
+ * controllers for left and right position and velocity states, the controllers
+ * only deal with the local pose. If the robot deviates from the path, there is
+ * no way for the controllers to correct and the robot may not reach the desired
+ * global pose. This is due to multiple endpoints existing for the robot which
+ * have the same encoder path arc lengths.
+ *
+ * Instead of using wheel path arc lengths (which are in the robot's local
+ * coordinate frame), nonlinear controllers like pure pursuit and Ramsete use
+ * global pose. The controller uses this extra information to guide a linear
+ * reference tracker like the PID controllers back in by adjusting the
+ * references of the PID controllers.
+ *
+ * The paper "Control of Wheeled Mobile Robots: An Experimental Overview"
+ * describes a nonlinear controller for a wheeled vehicle with unicycle-like
+ * kinematics; a global pose consisting of x, y, and theta; and a desired pose
+ * consisting of x_d, y_d, and theta_d. We call it Ramsete because that's the
+ * acronym for the title of the book it came from in Italian ("Robotica
+ * Articolata e Mobile per i SErvizi e le TEcnologie").
+ *
+ * See <https://file.tavsys.net/control/controls-engineering-in-frc.pdf> section
+ * on Ramsete unicycle controller for a derivation and analysis.
+ */
+class RamseteController {
+ public:
+  /**
+   * Construct a Ramsete unicycle controller.
+   *
+   * @param b    Tuning parameter (b > 0) for which larger values make
+   *             convergence more aggressive like a proportional term.
+   * @param zeta Tuning parameter (0 < zeta < 1) for which larger values provide
+   *             more damping in response.
+   */
+  RamseteController(double b, double zeta);
+
+  /**
+   * Construct a Ramsete unicycle controller. The default arguments for
+   * b and zeta of 2.0 and 0.7 have been well-tested to produce desireable
+   * results.
+   */
+  RamseteController() : RamseteController(2.0, 0.7) {}
+
+  /**
+   * Returns true if the pose error is within tolerance of the reference.
+   */
+  bool AtReference() const;
+
+  /**
+   * Sets the pose error which is considered tolerable for use with
+   * AtReference().
+   *
+   * @param poseTolerance Pose error which is tolerable.
+   */
+  void SetTolerance(const Pose2d& poseTolerance);
+
+  /**
+   * Returns the next output of the Ramsete controller.
+   *
+   * The reference pose, linear velocity, and angular velocity should come from
+   * a drivetrain trajectory.
+   *
+   * @param currentPose        The current pose.
+   * @param poseRef            The desired pose.
+   * @param linearVelocityRef  The desired linear velocity.
+   * @param angularVelocityRef The desired angular velocity.
+   */
+  ChassisSpeeds Calculate(const Pose2d& currentPose, const Pose2d& poseRef,
+                          units::meters_per_second_t linearVelocityRef,
+                          units::radians_per_second_t angularVelocityRef);
+
+  /**
+   * Returns the next output of the Ramsete controller.
+   *
+   * The reference pose, linear velocity, and angular velocity should come from
+   * a drivetrain trajectory.
+   *
+   * @param currentPose  The current pose.
+   * @param desiredState The desired pose, linear velocity, and angular velocity
+   *                     from a trajectory.
+   */
+  ChassisSpeeds Calculate(const Pose2d& currentPose,
+                          const Trajectory::State& desiredState);
+
+ private:
+  double m_b;
+  double m_zeta;
+
+  Pose2d m_poseError;
+  Pose2d m_poseTolerance;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/controller/SimpleMotorFeedforward.h b/wpilibc/src/main/native/include/frc/controller/SimpleMotorFeedforward.h
new file mode 100644
index 0000000..8f82cb9
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/controller/SimpleMotorFeedforward.h
@@ -0,0 +1,129 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+#include <wpi/MathExtras.h>
+
+namespace frc {
+/**
+ * A helper class that computes feedforward voltages for a simple
+ * permanent-magnet DC motor.
+ */
+template <class Distance>
+class SimpleMotorFeedforward {
+  using Velocity =
+      units::compound_unit<Distance, units::inverse<units::seconds>>;
+  using Acceleration =
+      units::compound_unit<Velocity, units::inverse<units::seconds>>;
+  using kv_unit = units::compound_unit<units::volts, units::inverse<Velocity>>;
+  using ka_unit =
+      units::compound_unit<units::volts, units::inverse<Acceleration>>;
+
+ public:
+  constexpr SimpleMotorFeedforward() = default;
+
+  /**
+   * Creates a new SimpleMotorFeedforward with the specified gains.
+   *
+   * @param kS The static gain, in volts.
+   * @param kV The velocity gain, in volt seconds per distance.
+   * @param kA The acceleration gain, in volt seconds^2 per distance.
+   */
+  constexpr SimpleMotorFeedforward(
+      units::volt_t kS, units::unit_t<kv_unit> kV,
+      units::unit_t<ka_unit> kA = units::unit_t<ka_unit>(0))
+      : kS(kS), kV(kV), kA(kA) {}
+
+  /**
+   * Calculates the feedforward from the gains and setpoints.
+   *
+   * @param velocity     The velocity setpoint, in distance per second.
+   * @param acceleration The acceleration setpoint, in distance per second^2.
+   * @return The computed feedforward, in volts.
+   */
+  constexpr units::volt_t Calculate(units::unit_t<Velocity> velocity,
+                                    units::unit_t<Acceleration> acceleration =
+                                        units::unit_t<Acceleration>(0)) const {
+    return kS * wpi::sgn(velocity) + kV * velocity + kA * acceleration;
+  }
+
+  // Rearranging the main equation from the calculate() method yields the
+  // formulas for the methods below:
+
+  /**
+   * Calculates the maximum achievable velocity given a maximum voltage supply
+   * and an acceleration.  Useful for ensuring that velocity and
+   * acceleration constraints for a trapezoidal profile are simultaneously
+   * achievable - enter the acceleration constraint, and this will give you
+   * a simultaneously-achievable velocity constraint.
+   *
+   * @param maxVoltage The maximum voltage that can be supplied to the motor.
+   * @param acceleration The acceleration of the motor.
+   * @return The maximum possible velocity at the given acceleration.
+   */
+  constexpr units::unit_t<Velocity> MaxAchievableVelocity(
+      units::volt_t maxVoltage, units::unit_t<Acceleration> acceleration) {
+    // Assume max velocity is positive
+    return (maxVoltage - kS - kA * acceleration) / kV;
+  }
+
+  /**
+   * Calculates the minimum achievable velocity given a maximum voltage supply
+   * and an acceleration.  Useful for ensuring that velocity and
+   * acceleration constraints for a trapezoidal profile are simultaneously
+   * achievable - enter the acceleration constraint, and this will give you
+   * a simultaneously-achievable velocity constraint.
+   *
+   * @param maxVoltage The maximum voltage that can be supplied to the motor.
+   * @param acceleration The acceleration of the motor.
+   * @return The minimum possible velocity at the given acceleration.
+   */
+  constexpr units::unit_t<Velocity> MinAchievableVelocity(
+      units::volt_t maxVoltage, units::unit_t<Acceleration> acceleration) {
+    // Assume min velocity is positive, ks flips sign
+    return (-maxVoltage + kS - kA * acceleration) / kV;
+  }
+
+  /**
+   * Calculates the maximum achievable acceleration given a maximum voltage
+   * supply and a velocity. Useful for ensuring that velocity and
+   * acceleration constraints for a trapezoidal profile are simultaneously
+   * achievable - enter the velocity constraint, and this will give you
+   * a simultaneously-achievable acceleration constraint.
+   *
+   * @param maxVoltage The maximum voltage that can be supplied to the motor.
+   * @param velocity The velocity of the motor.
+   * @return The maximum possible acceleration at the given velocity.
+   */
+  constexpr units::unit_t<Acceleration> MaxAchievableAcceleration(
+      units::volt_t maxVoltage, units::unit_t<Velocity> velocity) {
+    return (maxVoltage - kS * wpi::sgn(velocity) - kV * velocity) / kA;
+  }
+
+  /**
+   * Calculates the minimum achievable acceleration given a maximum voltage
+   * supply and a velocity. Useful for ensuring that velocity and
+   * acceleration constraints for a trapezoidal profile are simultaneously
+   * achievable - enter the velocity constraint, and this will give you
+   * a simultaneously-achievable acceleration constraint.
+   *
+   * @param maxVoltage The maximum voltage that can be supplied to the motor.
+   * @param velocity The velocity of the motor.
+   * @return The minimum possible acceleration at the given velocity.
+   */
+  constexpr units::unit_t<Acceleration> MinAchievableAcceleration(
+      units::volt_t maxVoltage, units::unit_t<Velocity> velocity) {
+    return MaxAchievableAcceleration(-maxVoltage, velocity);
+  }
+
+  units::volt_t kS{0};
+  units::unit_t<kv_unit> kV{0};
+  units::unit_t<ka_unit> kA{0};
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h
new file mode 100644
index 0000000..c6b705a
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h
@@ -0,0 +1,224 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/raw_ostream.h>
+
+#include "frc/drive/RobotDriveBase.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SpeedController;
+
+/**
+ * A class for driving differential drive/skid-steer drive platforms such as
+ * the Kit of Parts drive base, "tank drive", or West Coast Drive.
+ *
+ * These drive bases typically have drop-center / skid-steer with two or more
+ * wheels per side (e.g., 6WD or 8WD). This class takes a SpeedController per
+ * side. For four and six motor drivetrains, construct and pass in
+ * SpeedControllerGroup instances as follows.
+ *
+ * Four motor drivetrain:
+ * @code{.cpp}
+ * class Robot {
+ *  public:
+ *   frc::PWMVictorSPX m_frontLeft{1};
+ *   frc::PWMVictorSPX m_rearLeft{2};
+ *   frc::SpeedControllerGroup m_left{m_frontLeft, m_rearLeft};
+ *
+ *   frc::PWMVictorSPX m_frontRight{3};
+ *   frc::PWMVictorSPX m_rearRight{4};
+ *   frc::SpeedControllerGroup m_right{m_frontRight, m_rearRight};
+ *
+ *   frc::DifferentialDrive m_drive{m_left, m_right};
+ * };
+ * @endcode
+ *
+ * Six motor drivetrain:
+ * @code{.cpp}
+ * class Robot {
+ *  public:
+ *   frc::PWMVictorSPX m_frontLeft{1};
+ *   frc::PWMVictorSPX m_midLeft{2};
+ *   frc::PWMVictorSPX m_rearLeft{3};
+ *   frc::SpeedControllerGroup m_left{m_frontLeft, m_midLeft, m_rearLeft};
+ *
+ *   frc::PWMVictorSPX m_frontRight{4};
+ *   frc::PWMVictorSPX m_midRight{5};
+ *   frc::PWMVictorSPX m_rearRight{6};
+ *   frc::SpeedControllerGroup m_right{m_frontRight, m_midRight, m_rearRight};
+ *
+ *   frc::DifferentialDrive m_drive{m_left, m_right};
+ * };
+ * @endcode
+ *
+ * A differential drive robot has left and right wheels separated by an
+ * arbitrary width.
+ *
+ * Drive base diagram:
+ * <pre>
+ * |_______|
+ * | |   | |
+ *   |   |
+ * |_|___|_|
+ * |       |
+ * </pre>
+ *
+ * Each Drive() function provides different inverse kinematic relations for a
+ * differential drive robot. Motor outputs for the right side are negated, so
+ * motor direction inversion by the user is usually unnecessary.
+ *
+ * This library uses the NED axes convention (North-East-Down as external
+ * reference in the world frame):
+ * http://www.nuclearprojects.com/ins/images/axis_big.png.
+ *
+ * The positive X axis points ahead, the positive Y axis points to the right,
+ * and the positive Z axis points down. Rotations follow the right-hand rule, so
+ * clockwise rotation around the Z axis is positive.
+ *
+ * Inputs smaller then 0.02 will be set to 0, and larger values will be scaled
+ * so that the full range is still used. This deadband value can be changed
+ * with SetDeadband().
+ *
+ * <p>RobotDrive porting guide:
+ * <br>TankDrive(double, double, bool) is equivalent to
+ * RobotDrive#TankDrive(double, double, bool) if a deadband of 0 is used.
+ * <br>ArcadeDrive(double, double, bool) is equivalent to
+ * RobotDrive#ArcadeDrive(double, double, bool) if a deadband of 0 is used
+ * and the the rotation input is inverted eg ArcadeDrive(y, -rotation, false)
+ * <br>CurvatureDrive(double, double, bool) is similar in concept to
+ * RobotDrive#Drive(double, double) with the addition of a quick turn
+ * mode. However, it is not designed to give exactly the same response.
+ */
+class DifferentialDrive : public RobotDriveBase,
+                          public Sendable,
+                          public SendableHelper<DifferentialDrive> {
+ public:
+  static constexpr double kDefaultQuickStopThreshold = 0.2;
+  static constexpr double kDefaultQuickStopAlpha = 0.1;
+
+  /**
+   * Construct a DifferentialDrive.
+   *
+   * To pass multiple motors per side, use a SpeedControllerGroup. If a motor
+   * needs to be inverted, do so before passing it in.
+   */
+  DifferentialDrive(SpeedController& leftMotor, SpeedController& rightMotor);
+
+  ~DifferentialDrive() override = default;
+
+  DifferentialDrive(DifferentialDrive&&) = default;
+  DifferentialDrive& operator=(DifferentialDrive&&) = default;
+
+  /**
+   * Arcade drive method for differential drive platform.
+   *
+   * Note: Some drivers may prefer inverted rotation controls. This can be done
+   * by negating the value passed for rotation.
+   *
+   * @param xSpeed        The speed at which the robot should drive along the X
+   *                      axis [-1.0..1.0]. Forward is positive.
+   * @param zRotation     The rotation rate of the robot around the Z axis
+   *                      [-1.0..1.0]. Clockwise is positive.
+   * @param squareInputs If set, decreases the input sensitivity at low speeds.
+   */
+  void ArcadeDrive(double xSpeed, double zRotation, bool squareInputs = true);
+
+  /**
+   * Curvature drive method for differential drive platform.
+   *
+   * The rotation argument controls the curvature of the robot's path rather
+   * than its rate of heading change. This makes the robot more controllable at
+   * high speeds. Also handles the robot's quick turn functionality - "quick
+   * turn" overrides constant-curvature turning for turn-in-place maneuvers.
+   *
+   * @param xSpeed      The robot's speed along the X axis [-1.0..1.0]. Forward
+   *                    is positive.
+   * @param zRotation   The robot's rotation rate around the Z axis [-1.0..1.0].
+   *                    Clockwise is positive.
+   * @param isQuickTurn If set, overrides constant-curvature turning for
+   *                    turn-in-place maneuvers.
+   */
+  void CurvatureDrive(double xSpeed, double zRotation, bool isQuickTurn);
+
+  /**
+   * Tank drive method for differential drive platform.
+   *
+   * @param leftSpeed     The robot left side's speed along the X axis
+   *                      [-1.0..1.0]. Forward is positive.
+   * @param rightSpeed    The robot right side's speed along the X axis
+   *                      [-1.0..1.0]. Forward is positive.
+   * @param squareInputs If set, decreases the input sensitivity at low speeds.
+   */
+  void TankDrive(double leftSpeed, double rightSpeed, bool squareInputs = true);
+
+  /**
+   * Sets the QuickStop speed threshold in curvature drive.
+   *
+   * QuickStop compensates for the robot's moment of inertia when stopping after
+   * a QuickTurn.
+   *
+   * While QuickTurn is enabled, the QuickStop accumulator takes on the rotation
+   * rate value outputted by the low-pass filter when the robot's speed along
+   * the X axis is below the threshold. When QuickTurn is disabled, the
+   * accumulator's value is applied against the computed angular power request
+   * to slow the robot's rotation.
+   *
+   * @param threshold X speed below which quick stop accumulator will receive
+   *                  rotation rate values [0..1.0].
+   */
+  void SetQuickStopThreshold(double threshold);
+
+  /**
+   * Sets the low-pass filter gain for QuickStop in curvature drive.
+   *
+   * The low-pass filter filters incoming rotation rate commands to smooth out
+   * high frequency changes.
+   *
+   * @param alpha Low-pass filter gain [0.0..2.0]. Smaller values result in
+   *              slower output changes. Values between 1.0 and 2.0 result in
+   *              output oscillation. Values below 0.0 and above 2.0 are
+   *              unstable.
+   */
+  void SetQuickStopAlpha(double alpha);
+
+  /**
+   * Gets if the power sent to the right side of the drivetrain is multipled by
+   * -1.
+   *
+   * @return true if the right side is inverted
+   */
+  bool IsRightSideInverted() const;
+
+  /**
+   * Sets if the power sent to the right side of the drivetrain should be
+   * multipled by -1.
+   *
+   * @param rightSideInverted true if right side power should be multipled by -1
+   */
+  void SetRightSideInverted(bool rightSideInverted);
+
+  void StopMotor() override;
+  void GetDescription(wpi::raw_ostream& desc) const override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  SpeedController* m_leftMotor;
+  SpeedController* m_rightMotor;
+
+  double m_quickStopThreshold = kDefaultQuickStopThreshold;
+  double m_quickStopAlpha = kDefaultQuickStopAlpha;
+  double m_quickStopAccumulator = 0.0;
+  double m_rightSideInvertMultiplier = -1.0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/drive/KilloughDrive.h b/wpilibc/src/main/native/include/frc/drive/KilloughDrive.h
new file mode 100644
index 0000000..2cc1c91
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/drive/KilloughDrive.h
@@ -0,0 +1,146 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/raw_ostream.h>
+
+#include "frc/drive/RobotDriveBase.h"
+#include "frc/drive/Vector2d.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SpeedController;
+
+/**
+ * A class for driving Killough drive platforms.
+ *
+ * Killough drives are triangular with one omni wheel on each corner.
+ *
+ * Drive base diagram:
+ * <pre>
+ *  /_____\
+ * / \   / \
+ *    \ /
+ *    ---
+ * </pre>
+ *
+ * Each Drive() function provides different inverse kinematic relations for a
+ * Killough drive. The default wheel vectors are parallel to their respective
+ * opposite sides, but can be overridden. See the constructor for more
+ * information.
+ *
+ * This library uses the NED axes convention (North-East-Down as external
+ * reference in the world frame):
+ * http://www.nuclearprojects.com/ins/images/axis_big.png.
+ *
+ * The positive X axis points ahead, the positive Y axis points right, and the
+ * and the positive Z axis points down. Rotations follow the right-hand rule, so
+ * clockwise rotation around the Z axis is positive.
+ */
+class KilloughDrive : public RobotDriveBase,
+                      public Sendable,
+                      public SendableHelper<KilloughDrive> {
+ public:
+  static constexpr double kDefaultLeftMotorAngle = 60.0;
+  static constexpr double kDefaultRightMotorAngle = 120.0;
+  static constexpr double kDefaultBackMotorAngle = 270.0;
+
+  /**
+   * Construct a Killough drive with the given motors and default motor angles.
+   *
+   * The default motor angles make the wheels on each corner parallel to their
+   * respective opposite sides.
+   *
+   * If a motor needs to be inverted, do so before passing it in.
+   *
+   * @param leftMotor  The motor on the left corner.
+   * @param rightMotor The motor on the right corner.
+   * @param backMotor  The motor on the back corner.
+   */
+  KilloughDrive(SpeedController& leftMotor, SpeedController& rightMotor,
+                SpeedController& backMotor);
+
+  /**
+   * Construct a Killough drive with the given motors.
+   *
+   * Angles are measured in degrees clockwise from the positive X axis.
+   *
+   * @param leftMotor       The motor on the left corner.
+   * @param rightMotor      The motor on the right corner.
+   * @param backMotor       The motor on the back corner.
+   * @param leftMotorAngle  The angle of the left wheel's forward direction of
+   *                        travel.
+   * @param rightMotorAngle The angle of the right wheel's forward direction of
+   *                        travel.
+   * @param backMotorAngle  The angle of the back wheel's forward direction of
+   *                        travel.
+   */
+  KilloughDrive(SpeedController& leftMotor, SpeedController& rightMotor,
+                SpeedController& backMotor, double leftMotorAngle,
+                double rightMotorAngle, double backMotorAngle);
+
+  ~KilloughDrive() override = default;
+
+  KilloughDrive(KilloughDrive&&) = default;
+  KilloughDrive& operator=(KilloughDrive&&) = default;
+
+  /**
+   * Drive method for Killough platform.
+   *
+   * Angles are measured clockwise from the positive X axis. The robot's speed
+   * is independent from its angle or rotation rate.
+   *
+   * @param ySpeed    The robot's speed along the Y axis [-1.0..1.0]. Right is
+   *                  positive.
+   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Forward is
+   *                  positive.
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
+   *                  Clockwise is positive.
+   * @param gyroAngle The current angle reading from the gyro in degrees around
+   *                  the Z axis. Use this to implement field-oriented controls.
+   */
+  void DriveCartesian(double ySpeed, double xSpeed, double zRotation,
+                      double gyroAngle = 0.0);
+
+  /**
+   * Drive method for Killough platform.
+   *
+   * Angles are measured clockwise from the positive X axis. The robot's speed
+   * is independent from its angle or rotation rate.
+   *
+   * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is
+   *                  positive.
+   * @param angle     The angle around the Z axis at which the robot drives in
+   *                  degrees [-180..180].
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
+   *                  Clockwise is positive.
+   */
+  void DrivePolar(double magnitude, double angle, double zRotation);
+
+  void StopMotor() override;
+  void GetDescription(wpi::raw_ostream& desc) const override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  SpeedController* m_leftMotor;
+  SpeedController* m_rightMotor;
+  SpeedController* m_backMotor;
+
+  Vector2d m_leftVec;
+  Vector2d m_rightVec;
+  Vector2d m_backVec;
+
+  bool reported = false;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h b/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h
new file mode 100644
index 0000000..9ddb57e
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h
@@ -0,0 +1,150 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/raw_ostream.h>
+
+#include "frc/drive/RobotDriveBase.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SpeedController;
+
+/**
+ * A class for driving Mecanum drive platforms.
+ *
+ * Mecanum drives are rectangular with one wheel on each corner. Each wheel has
+ * rollers toed in 45 degrees toward the front or back. When looking at the
+ * wheels from the top, the roller axles should form an X across the robot.
+ *
+ * Drive base diagram:
+ * <pre>
+ * \\_______/
+ * \\ |   | /
+ *   |   |
+ * /_|___|_\\
+ * /       \\
+ * </pre>
+ *
+ * Each Drive() function provides different inverse kinematic relations for a
+ * Mecanum drive robot. Motor outputs for the right side are negated, so motor
+ * direction inversion by the user is usually unnecessary.
+ *
+ * This library uses the NED axes convention (North-East-Down as external
+ * reference in the world frame):
+ * http://www.nuclearprojects.com/ins/images/axis_big.png.
+ *
+ * The positive X axis points ahead, the positive Y axis points to the right,
+ * and the positive Z axis points down. Rotations follow the right-hand rule, so
+ * clockwise rotation around the Z axis is positive.
+ *
+ * Inputs smaller then 0.02 will be set to 0, and larger values will be scaled
+ * so that the full range is still used. This deadband value can be changed
+ * with SetDeadband().
+ *
+ * RobotDrive porting guide:
+ * <br>In MecanumDrive, the right side speed controllers are automatically
+ * inverted, while in RobotDrive, no speed controllers are automatically
+ * inverted.
+ * <br>DriveCartesian(double, double, double, double) is equivalent to
+ * RobotDrive#MecanumDrive_Cartesian(double, double, double, double)
+ * if a deadband of 0 is used, and the ySpeed and gyroAngle values are inverted
+ * compared to RobotDrive (eg DriveCartesian(xSpeed, -ySpeed, zRotation,
+ * -gyroAngle).
+ * <br>DrivePolar(double, double, double) is equivalent to
+ * RobotDrive#MecanumDrive_Polar(double, double, double) if a
+ * deadband of 0 is used.
+ */
+class MecanumDrive : public RobotDriveBase,
+                     public Sendable,
+                     public SendableHelper<MecanumDrive> {
+ public:
+  /**
+   * Construct a MecanumDrive.
+   *
+   * If a motor needs to be inverted, do so before passing it in.
+   */
+  MecanumDrive(SpeedController& frontLeftMotor, SpeedController& rearLeftMotor,
+               SpeedController& frontRightMotor,
+               SpeedController& rearRightMotor);
+
+  ~MecanumDrive() override = default;
+
+  MecanumDrive(MecanumDrive&&) = default;
+  MecanumDrive& operator=(MecanumDrive&&) = default;
+
+  /**
+   * Drive method for Mecanum platform.
+   *
+   * Angles are measured clockwise from the positive X axis. The robot's speed
+   * is independent from its angle or rotation rate.
+   *
+   * @param ySpeed    The robot's speed along the Y axis [-1.0..1.0]. Right is
+   *                  positive.
+   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Forward is
+   *                  positive.
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
+   *                  Clockwise is positive.
+   * @param gyroAngle The current angle reading from the gyro in degrees around
+   *                  the Z axis. Use this to implement field-oriented controls.
+   */
+  void DriveCartesian(double ySpeed, double xSpeed, double zRotation,
+                      double gyroAngle = 0.0);
+
+  /**
+   * Drive method for Mecanum platform.
+   *
+   * Angles are measured clockwise from the positive X axis. The robot's speed
+   * is independent from its angle or rotation rate.
+   *
+   * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is
+   *                  positive.
+   * @param angle     The angle around the Z axis at which the robot drives in
+   *                  degrees [-180..180].
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
+   *                  Clockwise is positive.
+   */
+  void DrivePolar(double magnitude, double angle, double zRotation);
+
+  /**
+   * Gets if the power sent to the right side of the drivetrain is multipled by
+   * -1.
+   *
+   * @return true if the right side is inverted
+   */
+  bool IsRightSideInverted() const;
+
+  /**
+   * Sets if the power sent to the right side of the drivetrain should be
+   * multipled by -1.
+   *
+   * @param rightSideInverted true if right side power should be multipled by -1
+   */
+  void SetRightSideInverted(bool rightSideInverted);
+
+  void StopMotor() override;
+  void GetDescription(wpi::raw_ostream& desc) const override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  SpeedController* m_frontLeftMotor;
+  SpeedController* m_rearLeftMotor;
+  SpeedController* m_frontRightMotor;
+  SpeedController* m_rearRightMotor;
+
+  double m_rightSideInvertMultiplier = -1.0;
+
+  bool reported = false;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h b/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h
new file mode 100644
index 0000000..ce9cbc5
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h
@@ -0,0 +1,96 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/MotorSafety.h"
+
+namespace frc {
+
+class SpeedController;
+
+/**
+ * Common base class for drive platforms.
+ */
+class RobotDriveBase : public MotorSafety {
+ public:
+  /**
+   * The location of a motor on the robot for the purpose of driving.
+   */
+  enum MotorType {
+    kFrontLeft = 0,
+    kFrontRight = 1,
+    kRearLeft = 2,
+    kRearRight = 3,
+    kLeft = 0,
+    kRight = 1,
+    kBack = 2
+  };
+
+  RobotDriveBase();
+  ~RobotDriveBase() override = default;
+
+  RobotDriveBase(RobotDriveBase&&) = default;
+  RobotDriveBase& operator=(RobotDriveBase&&) = default;
+
+  /**
+   * Sets the deadband applied to the drive inputs (e.g., joystick values).
+   *
+   * The default value is 0.02. Inputs smaller than the deadband are set to 0.0
+   * while inputs larger than the deadband are scaled from 0.0 to 1.0. See
+   * ApplyDeadband().
+   *
+   * @param deadband The deadband to set.
+   */
+  void SetDeadband(double deadband);
+
+  /**
+   * Configure the scaling factor for using RobotDrive with motor controllers in
+   * a mode other than PercentVbus or to limit the maximum output.
+   *
+   * @param maxOutput Multiplied with the output percentage computed by the
+   *                  drive functions.
+   */
+  void SetMaxOutput(double maxOutput);
+
+  /**
+   * Feed the motor safety object. Resets the timer that will stop the motors if
+   * it completes.
+   *
+   * @see MotorSafetyHelper::Feed()
+   */
+  void FeedWatchdog();
+
+  void StopMotor() override = 0;
+  void GetDescription(wpi::raw_ostream& desc) const override = 0;
+
+ protected:
+  /**
+   * Returns 0.0 if the given value is within the specified range around zero.
+   * The remaining range between the deadband and 1.0 is scaled from 0.0 to 1.0.
+   *
+   * @param value    value to clip
+   * @param deadband range around zero
+   */
+  double ApplyDeadband(double number, double deadband);
+
+  /**
+   * Normalize all wheel speeds if the magnitude of any wheel is greater than
+   * 1.0.
+   */
+  void Normalize(wpi::MutableArrayRef<double> wheelSpeeds);
+
+  double m_deadband = 0.02;
+  double m_maxOutput = 1.0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/drive/Vector2d.h b/wpilibc/src/main/native/include/frc/drive/Vector2d.h
new file mode 100644
index 0000000..c9bd08a
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/drive/Vector2d.h
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+/**
+ * This is a 2D vector struct that supports basic vector operations.
+ */
+struct Vector2d {
+  Vector2d() = default;
+  Vector2d(double x, double y);
+
+  /**
+   * Rotate a vector in Cartesian space.
+   *
+   * @param angle angle in degrees by which to rotate vector counter-clockwise.
+   */
+  void Rotate(double angle);
+
+  /**
+   * Returns dot product of this vector with argument.
+   *
+   * @param vec Vector with which to perform dot product.
+   */
+  double Dot(const Vector2d& vec) const;
+
+  /**
+   * Returns magnitude of vector.
+   */
+  double Magnitude() const;
+
+  /**
+   * Returns scalar projection of this vector onto argument.
+   *
+   * @param vec Vector onto which to project this vector.
+   */
+  double ScalarProject(const Vector2d& vec) const;
+
+  double x = 0.0;
+  double y = 0.0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/filters/Filter.h b/wpilibc/src/main/native/include/frc/filters/Filter.h
new file mode 100644
index 0000000..b200407
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/filters/Filter.h
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/deprecated.h>
+
+#include "frc/PIDSource.h"
+
+namespace frc {
+
+/**
+ * Interface for filters
+ */
+class Filter : public PIDSource {
+ public:
+  WPI_DEPRECATED("This class is no longer used.")
+  explicit Filter(PIDSource& source);
+  WPI_DEPRECATED("This class is no longer used.")
+  explicit Filter(std::shared_ptr<PIDSource> source);
+  virtual ~Filter() = default;
+
+  Filter(Filter&&) = default;
+  Filter& operator=(Filter&&) = default;
+
+  // PIDSource interface
+  void SetPIDSourceType(PIDSourceType pidSource) override;
+  PIDSourceType GetPIDSourceType() const override;
+  double PIDGet() override = 0;
+
+  /**
+   * Returns the current filter estimate without also inserting new data as
+   * PIDGet() would do.
+   *
+   * @return The current filter estimate
+   */
+  virtual double Get() const = 0;
+
+  /**
+   * Reset the filter state
+   */
+  virtual void Reset() = 0;
+
+ protected:
+  /**
+   * Calls PIDGet() of source
+   *
+   * @return Current value of source
+   */
+  double PIDGetSource();
+
+ private:
+  std::shared_ptr<PIDSource> m_source;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/filters/LinearDigitalFilter.h b/wpilibc/src/main/native/include/frc/filters/LinearDigitalFilter.h
new file mode 100644
index 0000000..0a2afd2
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/filters/LinearDigitalFilter.h
@@ -0,0 +1,224 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared 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 <wpi/ArrayRef.h>
+#include <wpi/circular_buffer.h>
+#include <wpi/deprecated.h>
+
+#include "frc/filters/Filter.h"
+
+namespace frc {
+
+/**
+ * This class implements a linear, digital filter. All types of FIR and IIR
+ * filters are supported. Static factory methods are provided to create commonly
+ * used types of filters.
+ *
+ * Filters are of the form:<br>
+ *  y[n] = (b0 * x[n] + b1 * x[n-1] + ... + bP * x[n-P]) -
+ *         (a0 * y[n-1] + a2 * y[n-2] + ... + aQ * y[n-Q])
+ *
+ * Where:<br>
+ *  y[n] is the output at time "n"<br>
+ *  x[n] is the input at time "n"<br>
+ *  y[n-1] is the output from the LAST time step ("n-1")<br>
+ *  x[n-1] is the input from the LAST time step ("n-1")<br>
+ *  b0...bP are the "feedforward" (FIR) gains<br>
+ *  a0...aQ are the "feedback" (IIR) gains<br>
+ * IMPORTANT! Note the "-" sign in front of the feedback term! This is a common
+ *            convention in signal processing.
+ *
+ * What can linear filters do? Basically, they can filter, or diminish, the
+ * effects of undesirable input frequencies. High frequencies, or rapid changes,
+ * can be indicative of sensor noise or be otherwise undesirable. A "low pass"
+ * filter smooths out the signal, reducing the impact of these high frequency
+ * components.  Likewise, a "high pass" filter gets rid of slow-moving signal
+ * components, letting you detect large changes more easily.
+ *
+ * Example FRC applications of filters:
+ *  - Getting rid of noise from an analog sensor input (note: the roboRIO's FPGA
+ *    can do this faster in hardware)
+ *  - Smoothing out joystick input to prevent the wheels from slipping or the
+ *    robot from tipping
+ *  - Smoothing motor commands so that unnecessary strain isn't put on
+ *    electrical or mechanical components
+ *  - If you use clever gains, you can make a PID controller out of this class!
+ *
+ * For more on filters, I highly recommend the following articles:<br>
+ *  http://en.wikipedia.org/wiki/Linear_filter<br>
+ *  http://en.wikipedia.org/wiki/Iir_filter<br>
+ *  http://en.wikipedia.org/wiki/Fir_filter<br>
+ *
+ * Note 1: PIDGet() should be called by the user on a known, regular period.
+ * You can set up a Notifier to do this (look at the WPILib PIDController
+ * class), or do it "inline" with code in a periodic function.
+ *
+ * Note 2: For ALL filters, gains are necessarily a function of frequency. If
+ * you make a filter that works well for you at, say, 100Hz, you will most
+ * definitely need to adjust the gains if you then want to run it at 200Hz!
+ * Combining this with Note 1 - the impetus is on YOU as a developer to make
+ * sure PIDGet() gets called at the desired, constant frequency!
+ */
+class LinearDigitalFilter : public Filter {
+ public:
+  /**
+   * Create a linear FIR or IIR filter.
+   *
+   * @param source  The PIDSource object that is used to get values
+   * @param ffGains The "feed forward" or FIR gains
+   * @param fbGains The "feed back" or IIR gains
+   */
+  WPI_DEPRECATED("Use LinearFilter class instead.")
+  LinearDigitalFilter(PIDSource& source, wpi::ArrayRef<double> ffGains,
+                      wpi::ArrayRef<double> fbGains);
+
+  /**
+   * Create a linear FIR or IIR filter.
+   *
+   * @param source  The PIDSource object that is used to get values
+   * @param ffGains The "feed forward" or FIR gains
+   * @param fbGains The "feed back" or IIR gains
+   */
+  WPI_DEPRECATED("Use LinearFilter class instead.")
+  LinearDigitalFilter(PIDSource& source, std::initializer_list<double> ffGains,
+                      std::initializer_list<double> fbGains);
+
+  /**
+   * Create a linear FIR or IIR filter.
+   *
+   * @param source  The PIDSource object that is used to get values
+   * @param ffGains The "feed forward" or FIR gains
+   * @param fbGains The "feed back" or IIR gains
+   */
+  WPI_DEPRECATED("Use LinearFilter class instead.")
+  LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                      wpi::ArrayRef<double> ffGains,
+                      wpi::ArrayRef<double> fbGains);
+
+  /**
+   * Create a linear FIR or IIR filter.
+   *
+   * @param source  The PIDSource object that is used to get values
+   * @param ffGains The "feed forward" or FIR gains
+   * @param fbGains The "feed back" or IIR gains
+   */
+  WPI_DEPRECATED("Use LinearFilter class instead.")
+  LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                      std::initializer_list<double> ffGains,
+                      std::initializer_list<double> fbGains);
+
+  LinearDigitalFilter(LinearDigitalFilter&&) = default;
+  LinearDigitalFilter& operator=(LinearDigitalFilter&&) = default;
+
+  // Static methods to create commonly used filters
+  /**
+   * Creates a one-pole IIR low-pass filter of the form:<br>
+   *   y[n] = (1 - gain) * x[n] + gain * y[n-1]<br>
+   * where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
+   *
+   * This filter is stable for time constants greater than zero.
+   *
+   * @param source       The PIDSource object that is used to get values
+   * @param timeConstant The discrete-time time constant in seconds
+   * @param period       The period in seconds between samples taken by the user
+   */
+  static LinearDigitalFilter SinglePoleIIR(PIDSource& source,
+                                           double timeConstant, double period);
+
+  /**
+   * Creates a first-order high-pass filter of the form:<br>
+   *   y[n] = gain * x[n] + (-gain) * x[n-1] + gain * y[n-1]<br>
+   * where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
+   *
+   * This filter is stable for time constants greater than zero.
+   *
+   * @param source       The PIDSource object that is used to get values
+   * @param timeConstant The discrete-time time constant in seconds
+   * @param period       The period in seconds between samples taken by the user
+   */
+  static LinearDigitalFilter HighPass(PIDSource& source, double timeConstant,
+                                      double period);
+
+  /**
+   * Creates a K-tap FIR moving average filter of the form:<br>
+   *   y[n] = 1/k * (x[k] + x[k-1] + … + x[0])
+   *
+   * This filter is always stable.
+   *
+   * @param source The PIDSource object that is used to get values
+   * @param taps   The number of samples to average over. Higher = smoother but
+   *               slower
+   */
+  static LinearDigitalFilter MovingAverage(PIDSource& source, int taps);
+
+  /**
+   * Creates a one-pole IIR low-pass filter of the form:<br>
+   *   y[n] = (1 - gain) * x[n] + gain * y[n-1]<br>
+   * where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
+   *
+   * This filter is stable for time constants greater than zero.
+   *
+   * @param source       The PIDSource object that is used to get values
+   * @param timeConstant The discrete-time time constant in seconds
+   * @param period       The period in seconds between samples taken by the user
+   */
+  static LinearDigitalFilter SinglePoleIIR(std::shared_ptr<PIDSource> source,
+                                           double timeConstant, double period);
+
+  /**
+   * Creates a first-order high-pass filter of the form:<br>
+   *   y[n] = gain * x[n] + (-gain) * x[n-1] + gain * y[n-1]<br>
+   * where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
+   *
+   * This filter is stable for time constants greater than zero.
+   *
+   * @param source       The PIDSource object that is used to get values
+   * @param timeConstant The discrete-time time constant in seconds
+   * @param period       The period in seconds between samples taken by the user
+   */
+  static LinearDigitalFilter HighPass(std::shared_ptr<PIDSource> source,
+                                      double timeConstant, double period);
+
+  /**
+   * Creates a K-tap FIR moving average filter of the form:<br>
+   *   y[n] = 1/k * (x[k] + x[k-1] + … + x[0])
+   *
+   * This filter is always stable.
+   *
+   * @param source The PIDSource object that is used to get values
+   * @param taps   The number of samples to average over. Higher = smoother but
+   *               slower
+   */
+  static LinearDigitalFilter MovingAverage(std::shared_ptr<PIDSource> source,
+                                           int taps);
+
+  // Filter interface
+  double Get() const override;
+  void Reset() override;
+
+  // PIDSource interface
+  /**
+   * Calculates the next value of the filter
+   *
+   * @return The filtered value at this step
+   */
+  double PIDGet() override;
+
+ private:
+  wpi::circular_buffer<double> m_inputs;
+  wpi::circular_buffer<double> m_outputs;
+  std::vector<double> m_inputGains;
+  std::vector<double> m_outputGains;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/geometry/Pose2d.h b/wpilibc/src/main/native/include/frc/geometry/Pose2d.h
new file mode 100644
index 0000000..46328a0
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/geometry/Pose2d.h
@@ -0,0 +1,179 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "Transform2d.h"
+#include "Translation2d.h"
+#include "Twist2d.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace frc {
+
+/**
+ * Represents a 2d pose containing translational and rotational elements.
+ */
+class Pose2d {
+ public:
+  /**
+   * Constructs a pose at the origin facing toward the positive X axis.
+   * (Translation2d{0, 0} and Rotation{0})
+   */
+  constexpr Pose2d() = default;
+
+  /**
+   * Constructs a pose with the specified translation and rotation.
+   *
+   * @param translation The translational component of the pose.
+   * @param rotation The rotational component of the pose.
+   */
+  Pose2d(Translation2d translation, Rotation2d rotation);
+
+  /**
+   * Convenience constructors that takes in x and y values directly instead of
+   * having to construct a Translation2d.
+   *
+   * @param x The x component of the translational component of the pose.
+   * @param y The y component of the translational component of the pose.
+   * @param rotation The rotational component of the pose.
+   */
+  Pose2d(units::meter_t x, units::meter_t y, Rotation2d rotation);
+
+  /**
+   * Transforms the pose by the given transformation and returns the new
+   * transformed pose.
+   *
+   * [x_new]    [cos, -sin, 0][transform.x]
+   * [y_new] += [sin,  cos, 0][transform.y]
+   * [t_new]    [0,    0,   1][transform.t]
+   *
+   * @param other The transform to transform the pose by.
+   *
+   * @return The transformed pose.
+   */
+  Pose2d operator+(const Transform2d& other) const;
+
+  /**
+   * Transforms the current pose by the transformation.
+   *
+   * This is similar to the + operator, except that it mutates the current
+   * object.
+   *
+   * @param other The transform to transform the pose by.
+   *
+   * @return Reference to the new mutated object.
+   */
+  Pose2d& operator+=(const Transform2d& other);
+
+  /**
+   * Returns the Transform2d that maps the one pose to another.
+   *
+   * @param other The initial pose of the transformation.
+   * @return The transform that maps the other pose to the current pose.
+   */
+  Transform2d operator-(const Pose2d& other) const;
+
+  /**
+   * Checks equality between this Pose2d and another object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are equal.
+   */
+  bool operator==(const Pose2d& other) const;
+
+  /**
+   * Checks inequality between this Pose2d and another object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are not equal.
+   */
+  bool operator!=(const Pose2d& other) const;
+
+  /**
+   * Returns the underlying translation.
+   *
+   * @return Reference to the translational component of the pose.
+   */
+  const Translation2d& Translation() const { return m_translation; }
+
+  /**
+   * Returns the underlying rotation.
+   *
+   * @return Reference to the rotational component of the pose.
+   */
+  const Rotation2d& Rotation() const { return m_rotation; }
+
+  /**
+   * Transforms the pose by the given transformation and returns the new pose.
+   * See + operator for the matrix multiplication performed.
+   *
+   * @param other The transform to transform the pose by.
+   *
+   * @return The transformed pose.
+   */
+  Pose2d TransformBy(const Transform2d& other) const;
+
+  /**
+   * Returns the other pose relative to the current pose.
+   *
+   * This function can often be used for trajectory tracking or pose
+   * stabilization algorithms to get the error between the reference and the
+   * current pose.
+   *
+   * @param other The pose that is the origin of the new coordinate frame that
+   * the current pose will be converted into.
+   *
+   * @return The current pose relative to the new origin pose.
+   */
+  Pose2d RelativeTo(const Pose2d& other) const;
+
+  /**
+   * Obtain a new Pose2d from a (constant curvature) velocity.
+   *
+   * See <https://file.tavsys.net/control/state-space-guide.pdf> section on
+   * nonlinear pose estimation for derivation.
+   *
+   * The twist is a change in pose in the robot's coordinate frame since the
+   * previous pose update. When the user runs exp() on the previous known
+   * field-relative pose with the argument being the twist, the user will
+   * receive the new field-relative pose.
+   *
+   * "Exp" represents the pose exponential, which is solving a differential
+   * equation moving the pose forward in time.
+   *
+   * @param twist The change in pose in the robot's coordinate frame since the
+   * previous pose update. For example, if a non-holonomic robot moves forward
+   * 0.01 meters and changes angle by 0.5 degrees since the previous pose
+   * update, the twist would be Twist2d{0.01, 0.0, toRadians(0.5)}
+   *
+   * @return The new pose of the robot.
+   */
+  Pose2d Exp(const Twist2d& twist) const;
+
+  /**
+   * Returns a Twist2d that maps this pose to the end pose. If c is the output
+   * of a.Log(b), then a.Exp(c) would yield b.
+   *
+   * @param end The end pose for the transformation.
+   *
+   * @return The twist that maps this to end.
+   */
+  Twist2d Log(const Pose2d& end) const;
+
+ private:
+  Translation2d m_translation;
+  Rotation2d m_rotation;
+};
+
+void to_json(wpi::json& json, const Pose2d& pose);
+
+void from_json(const wpi::json& json, Pose2d& pose);
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/geometry/Rotation2d.h b/wpilibc/src/main/native/include/frc/geometry/Rotation2d.h
new file mode 100644
index 0000000..b636513
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/geometry/Rotation2d.h
@@ -0,0 +1,186 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace frc {
+
+/**
+ * A rotation in a 2d coordinate frame represented a point on the unit circle
+ * (cosine and sine).
+ */
+class Rotation2d {
+ public:
+  /**
+   * Constructs a Rotation2d with a default angle of 0 degrees.
+   */
+  constexpr Rotation2d() = default;
+
+  /**
+   * Constructs a Rotation2d with the given radian value.
+   *
+   * @param value The value of the angle in radians.
+   */
+  Rotation2d(units::radian_t value);  // NOLINT(runtime/explicit)
+
+  /**
+   * Constructs a Rotation2d with the given x and y (cosine and sine)
+   * components. The x and y don't have to be normalized.
+   *
+   * @param x The x component or cosine of the rotation.
+   * @param y The y component or sine of the rotation.
+   */
+  Rotation2d(double x, double y);
+
+  /**
+   * Adds two rotations together, with the result being bounded between -pi and
+   * pi.
+   *
+   * For example, Rotation2d.FromDegrees(30) + Rotation2d.FromDegrees(60) =
+   * Rotation2d{-pi/2}
+   *
+   * @param other The rotation to add.
+   *
+   * @return The sum of the two rotations.
+   */
+  Rotation2d operator+(const Rotation2d& other) const;
+
+  /**
+   * Adds a rotation to the current rotation.
+   *
+   * This is similar to the + operator except that it mutates the current
+   * object.
+   *
+   * @param other The rotation to add.
+   *
+   * @return The reference to the new mutated object.
+   */
+  Rotation2d& operator+=(const Rotation2d& other);
+
+  /**
+   * Subtracts the new rotation from the current rotation and returns the new
+   * rotation.
+   *
+   * For example, Rotation2d.FromDegrees(10) - Rotation2d.FromDegrees(100) =
+   * Rotation2d{-pi/2}
+   *
+   * @param other The rotation to subtract.
+   *
+   * @return The difference between the two rotations.
+   */
+  Rotation2d operator-(const Rotation2d& other) const;
+
+  /**
+   * Subtracts the new rotation from the current rotation.
+   *
+   * This is similar to the - operator except that it mutates the current
+   * object.
+   *
+   * @param other The rotation to subtract.
+   *
+   * @return The reference to the new mutated object.
+   */
+  Rotation2d& operator-=(const Rotation2d& other);
+
+  /**
+   * Takes the inverse of the current rotation. This is simply the negative of
+   * the current angular value.
+   *
+   * @return The inverse of the current rotation.
+   */
+  Rotation2d operator-() const;
+
+  /**
+   * Multiplies the current rotation by a scalar.
+   * @param scalar The scalar.
+   *
+   * @return The new scaled Rotation2d.
+   */
+  Rotation2d operator*(double scalar) const;
+
+  /**
+   * Checks equality between this Rotation2d and another object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are equal.
+   */
+  bool operator==(const Rotation2d& other) const;
+
+  /**
+   * Checks inequality between this Rotation2d and another object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are not equal.
+   */
+  bool operator!=(const Rotation2d& other) const;
+
+  /**
+   * Adds the new rotation to the current rotation using a rotation matrix.
+   *
+   * [cos_new]   [other.cos, -other.sin][cos]
+   * [sin_new] = [other.sin,  other.cos][sin]
+   *
+   * value_new = std::atan2(cos_new, sin_new)
+   *
+   * @param other The rotation to rotate by.
+   *
+   * @return The new rotated Rotation2d.
+   */
+  Rotation2d RotateBy(const Rotation2d& other) const;
+
+  /**
+   * Returns the radian value of the rotation.
+   *
+   * @return The radian value of the rotation.
+   */
+  units::radian_t Radians() const { return m_value; }
+
+  /**
+   * Returns the degree value of the rotation.
+   *
+   * @return The degree value of the rotation.
+   */
+  units::degree_t Degrees() const { return m_value; }
+
+  /**
+   * Returns the cosine of the rotation.
+   *
+   * @return The cosine of the rotation.
+   */
+  double Cos() const { return m_cos; }
+
+  /**
+   * Returns the sine of the rotation.
+   *
+   * @return The sine of the rotation.
+   */
+  double Sin() const { return m_sin; }
+
+  /**
+   * Returns the tangent of the rotation.
+   *
+   * @return The tangent of the rotation.
+   */
+  double Tan() const { return m_sin / m_cos; }
+
+ private:
+  units::radian_t m_value = 0_deg;
+  double m_cos = 1;
+  double m_sin = 0;
+};
+
+void to_json(wpi::json& json, const Rotation2d& rotation);
+
+void from_json(const wpi::json& json, Rotation2d& rotation);
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/geometry/Transform2d.h b/wpilibc/src/main/native/include/frc/geometry/Transform2d.h
new file mode 100644
index 0000000..c75fbeb
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/geometry/Transform2d.h
@@ -0,0 +1,86 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "Translation2d.h"
+
+namespace frc {
+
+class Pose2d;
+
+/**
+ * Represents a transformation for a Pose2d.
+ */
+class Transform2d {
+ public:
+  /**
+   * Constructs the transform that maps the initial pose to the final pose.
+   *
+   * @param initial The initial pose for the transformation.
+   * @param final The final pose for the transformation.
+   */
+  Transform2d(Pose2d initial, Pose2d final);
+
+  /**
+   * Constructs a transform with the given translation and rotation components.
+   *
+   * @param translation Translational component of the transform.
+   * @param rotation Rotational component of the transform.
+   */
+  Transform2d(Translation2d translation, Rotation2d rotation);
+
+  /**
+   * Constructs the identity transform -- maps an initial pose to itself.
+   */
+  constexpr Transform2d() = default;
+
+  /**
+   * Returns the translation component of the transformation.
+   *
+   * @return Reference to the translational component of the transform.
+   */
+  const Translation2d& Translation() const { return m_translation; }
+
+  /**
+   * Returns the rotational component of the transformation.
+   *
+   * @return Reference to the rotational component of the transform.
+   */
+  const Rotation2d& Rotation() const { return m_rotation; }
+
+  /**
+   * Scales the transform by the scalar.
+   *
+   * @param scalar The scalar.
+   * @return The scaled Transform2d.
+   */
+  Transform2d operator*(double scalar) const {
+    return Transform2d(m_translation * scalar, m_rotation * scalar);
+  }
+
+  /**
+   * Checks equality between this Transform2d and another object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are equal.
+   */
+  bool operator==(const Transform2d& other) const;
+
+  /**
+   * Checks inequality between this Transform2d and another object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are not equal.
+   */
+  bool operator!=(const Transform2d& other) const;
+
+ private:
+  Translation2d m_translation;
+  Rotation2d m_rotation;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/geometry/Translation2d.h b/wpilibc/src/main/native/include/frc/geometry/Translation2d.h
new file mode 100644
index 0000000..90c61e2
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/geometry/Translation2d.h
@@ -0,0 +1,223 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+
+#include "Rotation2d.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace frc {
+
+/**
+ * Represents a translation in 2d space.
+ * This object can be used to represent a point or a vector.
+ *
+ * This assumes that you are using conventional mathematical axes.
+ * When the robot is placed on the origin, facing toward the X direction,
+ * moving forward increases the X, whereas moving to the left increases the Y.
+ */
+class Translation2d {
+ public:
+  /**
+   * Constructs a Translation2d with X and Y components equal to zero.
+   */
+  constexpr Translation2d() = default;
+
+  /**
+   * Constructs a Translation2d with the X and Y components equal to the
+   * provided values.
+   *
+   * @param x The x component of the translation.
+   * @param y The y component of the translation.
+   */
+  Translation2d(units::meter_t x, units::meter_t y);
+
+  /**
+   * Calculates the distance between two translations in 2d space.
+   *
+   * This function uses the pythagorean theorem to calculate the distance.
+   * distance = std::sqrt((x2 - x1)^2 + (y2 - y1)^2)
+   *
+   * @param other The translation to compute the distance to.
+   *
+   * @return The distance between the two translations.
+   */
+  units::meter_t Distance(const Translation2d& other) const;
+
+  /**
+   * Returns the X component of the translation.
+   *
+   * @return The x component of the translation.
+   */
+  units::meter_t X() const { return m_x; }
+
+  /**
+   * Returns the Y component of the translation.
+   *
+   * @return The y component of the translation.
+   */
+  units::meter_t Y() const { return m_y; }
+
+  /**
+   * Returns the norm, or distance from the origin to the translation.
+   *
+   * @return The norm of the translation.
+   */
+  units::meter_t Norm() const;
+
+  /**
+   * Applies a rotation to the translation in 2d space.
+   *
+   * This multiplies the translation vector by a counterclockwise rotation
+   * matrix of the given angle.
+   *
+   * [x_new]   [other.cos, -other.sin][x]
+   * [y_new] = [other.sin,  other.cos][y]
+   *
+   * For example, rotating a Translation2d of {2, 0} by 90 degrees will return a
+   * Translation2d of {0, 2}.
+   *
+   * @param other The rotation to rotate the translation by.
+   *
+   * @return The new rotated translation.
+   */
+  Translation2d RotateBy(const Rotation2d& other) const;
+
+  /**
+   * Adds two translations in 2d space and returns the sum. This is similar to
+   * vector addition.
+   *
+   * For example, Translation2d{1.0, 2.5} + Translation2d{2.0, 5.5} =
+   * Translation2d{3.0, 8.0}
+   *
+   * @param other The translation to add.
+   *
+   * @return The sum of the translations.
+   */
+  Translation2d operator+(const Translation2d& other) const;
+
+  /**
+   * Adds the new translation to the current translation.
+   *
+   * This is similar to the + operator, except that the current object is
+   * mutated.
+   *
+   * @param other The translation to add.
+   *
+   * @return The reference to the new mutated object.
+   */
+  Translation2d& operator+=(const Translation2d& other);
+
+  /**
+   * Subtracts the other translation from the other translation and returns the
+   * difference.
+   *
+   * For example, Translation2d{5.0, 4.0} - Translation2d{1.0, 2.0} =
+   * Translation2d{4.0, 2.0}
+   *
+   * @param other The translation to subtract.
+   *
+   * @return The difference between the two translations.
+   */
+  Translation2d operator-(const Translation2d& other) const;
+
+  /**
+   * Subtracts the new translation from the current translation.
+   *
+   * This is similar to the - operator, except that the current object is
+   * mutated.
+   *
+   * @param other The translation to subtract.
+   *
+   * @return The reference to the new mutated object.
+   */
+  Translation2d& operator-=(const Translation2d& other);
+
+  /**
+   * Returns the inverse of the current translation. This is equivalent to
+   * rotating by 180 degrees, flipping the point over both axes, or simply
+   * negating both components of the translation.
+   *
+   * @return The inverse of the current translation.
+   */
+  Translation2d operator-() const;
+
+  /**
+   * Multiplies the translation by a scalar and returns the new translation.
+   *
+   * For example, Translation2d{2.0, 2.5} * 2 = Translation2d{4.0, 5.0}
+   *
+   * @param scalar The scalar to multiply by.
+   *
+   * @return The scaled translation.
+   */
+  Translation2d operator*(double scalar) const;
+
+  /**
+   * Multiplies the current translation by a scalar.
+   *
+   * This is similar to the * operator, except that current object is mutated.
+   *
+   * @param scalar The scalar to multiply by.
+   *
+   * @return The reference to the new mutated object.
+   */
+  Translation2d& operator*=(double scalar);
+
+  /**
+   * Divides the translation by a scalar and returns the new translation.
+   *
+   * For example, Translation2d{2.0, 2.5} / 2 = Translation2d{1.0, 1.25}
+   *
+   * @param scalar The scalar to divide by.
+   *
+   * @return The scaled translation.
+   */
+  Translation2d operator/(double scalar) const;
+
+  /**
+   * Checks equality between this Translation2d and another object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are equal.
+   */
+  bool operator==(const Translation2d& other) const;
+
+  /**
+   * Checks inequality between this Translation2d and another object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are not equal.
+   */
+  bool operator!=(const Translation2d& other) const;
+
+  /*
+   * Divides the current translation by a scalar.
+   *
+   * This is similar to the / operator, except that current object is mutated.
+   *
+   * @param scalar The scalar to divide by.
+   *
+   * @return The reference to the new mutated object.
+   */
+  Translation2d& operator/=(double scalar);
+
+ private:
+  units::meter_t m_x = 0_m;
+  units::meter_t m_y = 0_m;
+};
+
+void to_json(wpi::json& json, const Translation2d& state);
+
+void from_json(const wpi::json& json, Translation2d& state);
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/geometry/Twist2d.h b/wpilibc/src/main/native/include/frc/geometry/Twist2d.h
new file mode 100644
index 0000000..ab246a0
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/geometry/Twist2d.h
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+#include <units/units.h>
+
+namespace frc {
+/**
+ * A change in distance along arc since the last pose update. We can use ideas
+ * from differential calculus to create new Pose2ds from a Twist2d and vise
+ * versa.
+ *
+ * A Twist can be used to represent a difference between two poses.
+ */
+struct Twist2d {
+  /**
+   * Linear "dx" component
+   */
+  units::meter_t dx = 0_m;
+
+  /**
+   * Linear "dy" component
+   */
+  units::meter_t dy = 0_m;
+
+  /**
+   * Angular "dtheta" component (radians)
+   */
+  units::radian_t dtheta = 0_rad;
+
+  /**
+   * Checks equality between this Twist2d and another object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are equal.
+   */
+  bool operator==(const Twist2d& other) const {
+    return units::math::abs(dx - other.dx) < 1E-9_m &&
+           units::math::abs(dy - other.dy) < 1E-9_m &&
+           units::math::abs(dtheta - other.dtheta) < 1E-9_rad;
+  }
+
+  /**
+   * Checks inequality between this Twist2d and another object.
+   *
+   * @param other The other object.
+   * @return Whether the two objects are not equal.
+   */
+  bool operator!=(const Twist2d& other) const { return !operator==(other); }
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/interfaces/Accelerometer.h b/wpilibc/src/main/native/include/frc/interfaces/Accelerometer.h
new file mode 100644
index 0000000..499ba5b
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/interfaces/Accelerometer.h
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+/**
+ * Interface for 3-axis accelerometers.
+ */
+class Accelerometer {
+ public:
+  Accelerometer() = default;
+  virtual ~Accelerometer() = default;
+
+  Accelerometer(Accelerometer&&) = default;
+  Accelerometer& operator=(Accelerometer&&) = default;
+
+  enum Range { kRange_2G = 0, kRange_4G = 1, kRange_8G = 2, kRange_16G = 3 };
+
+  /**
+   * Common interface for setting the measuring range of an accelerometer.
+   *
+   * @param range The maximum acceleration, positive or negative, that the
+   *              accelerometer will measure. Not all accelerometers support all
+   *              ranges.
+   */
+  virtual void SetRange(Range range) = 0;
+
+  /**
+   * Common interface for getting the x axis acceleration.
+   *
+   * @return The acceleration along the x axis in g-forces
+   */
+  virtual double GetX() = 0;
+
+  /**
+   * Common interface for getting the y axis acceleration.
+   *
+   * @return The acceleration along the y axis in g-forces
+   */
+  virtual double GetY() = 0;
+
+  /**
+   * Common interface for getting the z axis acceleration.
+   *
+   * @return The acceleration along the z axis in g-forces
+   */
+  virtual double GetZ() = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/interfaces/Gyro.h b/wpilibc/src/main/native/include/frc/interfaces/Gyro.h
new file mode 100644
index 0000000..b5aa332
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/interfaces/Gyro.h
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+/**
+ * Interface for yaw rate gyros.
+ */
+class Gyro {
+ public:
+  Gyro() = default;
+  virtual ~Gyro() = default;
+
+  Gyro(Gyro&&) = default;
+  Gyro& operator=(Gyro&&) = default;
+
+  /**
+   * Calibrate the gyro by running for a number of samples and computing the
+   * center value. Then use the center value as the Accumulator center value for
+   * subsequent measurements. It's important to make sure that the robot is not
+   * moving while the centering calculations are in progress, this is typically
+   * done when the robot is first turned on while it's sitting at rest before
+   * the competition starts.
+   */
+  virtual void Calibrate() = 0;
+
+  /**
+   * Reset the gyro. Resets the gyro to a heading of zero. This can be used if
+   * there is significant drift in the gyro and it needs to be recalibrated
+   * after it has been running.
+   */
+  virtual void Reset() = 0;
+
+  /**
+   * Return the actual angle in degrees that the robot is currently facing.
+   *
+   * The angle is based on the current accumulator value corrected by the
+   * oversampling rate, the gyro type and the A/D calibration values. The angle
+   * is continuous, that is it will continue from 360 to 361 degrees. This
+   * allows algorithms that wouldn't want to see a discontinuity in the gyro
+   * output as it sweeps past from 360 to 0 on the second time around.
+   *
+   * The angle is expected to increase as the gyro turns clockwise when looked
+   * at from the top. It needs to follow NED axis conventions in order to work
+   * properly with dependent control loops.
+   *
+   * @return the current heading of the robot in degrees. This heading is based
+   *         on integration of the returned rate from the gyro.
+   */
+  virtual double GetAngle() const = 0;
+
+  /**
+   * Return the rate of rotation of the gyro.
+   *
+   * The rate is based on the most recent reading of the gyro analog value.
+   *
+   * The rate is expected to be positive as the gyro turns clockwise when looked
+   * at from the top. It needs to follow NED axis conventions in order to work
+   * properly with dependent control loops.
+   *
+   * @return the current rate in degrees per second
+   */
+  virtual double GetRate() const = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/interfaces/Potentiometer.h b/wpilibc/src/main/native/include/frc/interfaces/Potentiometer.h
new file mode 100644
index 0000000..219e6ba
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/interfaces/Potentiometer.h
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PIDSource.h"
+
+namespace frc {
+
+/**
+ * Interface for potentiometers.
+ */
+class Potentiometer : public PIDSource {
+ public:
+  Potentiometer() = default;
+  virtual ~Potentiometer() = default;
+
+  Potentiometer(Potentiometer&&) = default;
+  Potentiometer& operator=(Potentiometer&&) = default;
+
+  /**
+   * Common interface for getting the current value of a potentiometer.
+   *
+   * @return The current set speed. Value is between -1.0 and 1.0.
+   */
+  virtual double Get() const = 0;
+
+  void SetPIDSourceType(PIDSourceType pidSource) override;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/kinematics/ChassisSpeeds.h b/wpilibc/src/main/native/include/frc/kinematics/ChassisSpeeds.h
new file mode 100644
index 0000000..8c772c0
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/kinematics/ChassisSpeeds.h
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+
+#include "frc/geometry/Rotation2d.h"
+
+namespace frc {
+/**
+ * Represents the speed of a robot chassis. Although this struct contains
+ * similar members compared to a Twist2d, they do NOT represent the same thing.
+ * Whereas a Twist2d represents a change in pose w.r.t to the robot frame of
+ * reference, this ChassisSpeeds struct represents a velocity w.r.t to the robot
+ * frame of reference.
+ *
+ * A strictly non-holonomic drivetrain, such as a differential drive, should
+ * never have a dy component because it can never move sideways. Holonomic
+ * drivetrains such as swerve and mecanum will often have all three components.
+ */
+struct ChassisSpeeds {
+  /**
+   * Represents forward velocity w.r.t the robot frame of reference. (Fwd is +)
+   */
+  units::meters_per_second_t vx = 0_mps;
+
+  /**
+   * Represents strafe velocity w.r.t the robot frame of reference. (Left is +)
+   */
+  units::meters_per_second_t vy = 0_mps;
+
+  /**
+   * Represents the angular velocity of the robot frame. (CCW is +)
+   */
+  units::radians_per_second_t omega = 0_rad_per_s;
+
+  /**
+   * Converts a user provided field-relative set of speeds into a robot-relative
+   * ChassisSpeeds object.
+   *
+   * @param vx The component of speed in the x direction relative to the field.
+   * Positive x is away from your alliance wall.
+   * @param vy The component of speed in the y direction relative to the field.
+   * Positive y is to your left when standing behind the alliance wall.
+   * @param omega The angular rate of the robot.
+   * @param robotAngle The angle of the robot as measured by a gyroscope. The
+   * robot's angle is considered to be zero when it is facing directly away from
+   * your alliance station wall. Remember that this should be CCW positive.
+   *
+   * @return ChassisSpeeds object representing the speeds in the robot's frame
+   * of reference.
+   */
+  static ChassisSpeeds FromFieldRelativeSpeeds(
+      units::meters_per_second_t vx, units::meters_per_second_t vy,
+      units::radians_per_second_t omega, const Rotation2d& robotAngle) {
+    return {vx * robotAngle.Cos() + vy * robotAngle.Sin(),
+            -vx * robotAngle.Sin() + vy * robotAngle.Cos(), omega};
+  }
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h b/wpilibc/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h
new file mode 100644
index 0000000..e986029
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/kinematics/DifferentialDriveKinematics.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared 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/FRCUsageReporting.h>
+#include <units/units.h>
+
+#include "frc/kinematics/ChassisSpeeds.h"
+#include "frc/kinematics/DifferentialDriveWheelSpeeds.h"
+
+namespace frc {
+/**
+ * Helper class that converts a chassis velocity (dx and dtheta components) to
+ * left and right wheel velocities for a differential drive.
+ *
+ * Inverse kinematics converts a desired chassis speed into left and right
+ * velocity components whereas forward kinematics converts left and right
+ * component velocities into a linear and angular chassis speed.
+ */
+class DifferentialDriveKinematics {
+ public:
+  /**
+   * Constructs a differential drive kinematics object.
+   *
+   * @param trackWidth The track width of the drivetrain. Theoretically, this is
+   * the distance between the left wheels and right wheels. However, the
+   * empirical value may be larger than the physical measured value due to
+   * scrubbing effects.
+   */
+  explicit DifferentialDriveKinematics(units::meter_t trackWidth)
+      : trackWidth(trackWidth) {
+    HAL_Report(HALUsageReporting::kResourceType_Kinematics,
+               HALUsageReporting::kKinematics_DifferentialDrive);
+  }
+
+  /**
+   * Returns a chassis speed from left and right component velocities using
+   * forward kinematics.
+   *
+   * @param wheelSpeeds The left and right velocities.
+   * @return The chassis speed.
+   */
+  constexpr ChassisSpeeds ToChassisSpeeds(
+      const DifferentialDriveWheelSpeeds& wheelSpeeds) const {
+    return {(wheelSpeeds.left + wheelSpeeds.right) / 2.0, 0_mps,
+            (wheelSpeeds.right - wheelSpeeds.left) / trackWidth * 1_rad};
+  }
+
+  /**
+   * Returns left and right component velocities from a chassis speed using
+   * inverse kinematics.
+   *
+   * @param chassisSpeeds The linear and angular (dx and dtheta) components that
+   * represent the chassis' speed.
+   * @return The left and right velocities.
+   */
+  constexpr DifferentialDriveWheelSpeeds ToWheelSpeeds(
+      const ChassisSpeeds& chassisSpeeds) const {
+    return {chassisSpeeds.vx - trackWidth / 2 * chassisSpeeds.omega / 1_rad,
+            chassisSpeeds.vx + trackWidth / 2 * chassisSpeeds.omega / 1_rad};
+  }
+
+  units::meter_t trackWidth;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/kinematics/DifferentialDriveOdometry.h b/wpilibc/src/main/native/include/frc/kinematics/DifferentialDriveOdometry.h
new file mode 100644
index 0000000..379839d
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/kinematics/DifferentialDriveOdometry.h
@@ -0,0 +1,89 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+
+#include "DifferentialDriveKinematics.h"
+#include "frc/geometry/Pose2d.h"
+#include "frc2/Timer.h"
+
+namespace frc {
+/**
+ * Class for differential drive odometry. Odometry allows you to track the
+ * robot's position on the field over the course of a match using readings from
+ * 2 encoders and a gyroscope.
+ *
+ * Teams can use odometry during the autonomous period for complex tasks like
+ * path following. Furthermore, odometry can be used for latency compensation
+ * when using computer-vision systems.
+ *
+ * It is important that you reset your encoders to zero before using this class.
+ * Any subsequent pose resets also require the encoders to be reset to zero.
+ */
+class DifferentialDriveOdometry {
+ public:
+  /**
+   * Constructs a DifferentialDriveOdometry object.
+   *
+   * @param gyroAngle The angle reported by the gyroscope.
+   * @param initialPose The starting position of the robot on the field.
+   */
+  explicit DifferentialDriveOdometry(const Rotation2d& gyroAngle,
+                                     const Pose2d& initialPose = Pose2d());
+
+  /**
+   * Resets the robot's position on the field.
+   *
+   * You NEED to reset your encoders (to zero) when calling this method.
+   *
+   * The gyroscope angle does not need to be reset here on the user's robot
+   * code. The library automatically takes care of offsetting the gyro angle.
+   *
+   * @param pose The position on the field that your robot is at.
+   * @param gyroAngle The angle reported by the gyroscope.
+   */
+  void ResetPosition(const Pose2d& pose, const Rotation2d& gyroAngle) {
+    m_pose = pose;
+    m_previousAngle = pose.Rotation();
+    m_gyroOffset = m_pose.Rotation() - gyroAngle;
+
+    m_prevLeftDistance = 0_m;
+    m_prevRightDistance = 0_m;
+  }
+
+  /**
+   * Returns the position of the robot on the field.
+   * @return The pose of the robot.
+   */
+  const Pose2d& GetPose() const { return m_pose; }
+
+  /**
+   * Updates the robot position on the field using distance measurements from
+   * encoders. This method is more numerically accurate than using velocities to
+   * integrate the pose and is also advantageous for teams that are using lower
+   * CPR encoders.
+   *
+   * @param gyroAngle The angle reported by the gyroscope.
+   * @param leftDistance The distance traveled by the left encoder.
+   * @param rightDistance The distance traveled by the right encoder.
+   * @return The new pose of the robot.
+   */
+  const Pose2d& Update(const Rotation2d& gyroAngle, units::meter_t leftDistance,
+                       units::meter_t rightDistance);
+
+ private:
+  Pose2d m_pose;
+
+  Rotation2d m_gyroOffset;
+  Rotation2d m_previousAngle;
+
+  units::meter_t m_prevLeftDistance = 0_m;
+  units::meter_t m_prevRightDistance = 0_m;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/kinematics/DifferentialDriveWheelSpeeds.h b/wpilibc/src/main/native/include/frc/kinematics/DifferentialDriveWheelSpeeds.h
new file mode 100644
index 0000000..66bd84e
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/kinematics/DifferentialDriveWheelSpeeds.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+
+namespace frc {
+/**
+ * Represents the wheel speeds for a differential drive drivetrain.
+ */
+struct DifferentialDriveWheelSpeeds {
+  /**
+   * Speed of the left side of the robot.
+   */
+  units::meters_per_second_t left = 0_mps;
+
+  /**
+   * Speed of the right side of the robot.
+   */
+  units::meters_per_second_t right = 0_mps;
+
+  /**
+   * Normalizes the wheel speeds using some max attainable speed. Sometimes,
+   * after inverse kinematics, the requested speed from a/several modules may be
+   * above the max attainable speed for the driving motor on that module. To fix
+   * this issue, one can "normalize" all the wheel speeds to make sure that all
+   * requested module speeds are below the absolute threshold, while maintaining
+   * the ratio of speeds between modules.
+   *
+   * @param attainableMaxSpeed The absolute max speed that a wheel can reach.
+   */
+  void Normalize(units::meters_per_second_t attainableMaxSpeed);
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h b/wpilibc/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h
new file mode 100644
index 0000000..47b1b34
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/kinematics/MecanumDriveKinematics.h
@@ -0,0 +1,144 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <Eigen/Core>
+#include <Eigen/QR>
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/geometry/Translation2d.h"
+#include "frc/kinematics/ChassisSpeeds.h"
+#include "frc/kinematics/MecanumDriveWheelSpeeds.h"
+
+namespace frc {
+
+/**
+ * Helper class that converts a chassis velocity (dx, dy, and dtheta components)
+ * into individual wheel speeds.
+ *
+ * The inverse kinematics (converting from a desired chassis velocity to
+ * individual wheel speeds) uses the relative locations of the wheels with
+ * respect to the center of rotation. The center of rotation for inverse
+ * kinematics is also variable. This means that you can set your set your center
+ * of rotation in a corner of the robot to perform special evasion manuevers.
+ *
+ * Forward kinematics (converting an array of wheel speeds into the overall
+ * chassis motion) is performs the exact opposite of what inverse kinematics
+ * does. Since this is an overdetermined system (more equations than variables),
+ * we use a least-squares approximation.
+ *
+ * The inverse kinematics: [wheelSpeeds] = [wheelLocations] * [chassisSpeeds]
+ * We take the Moore-Penrose pseudoinverse of [wheelLocations] and then
+ * multiply by [wheelSpeeds] to get our chassis speeds.
+ *
+ * Forward kinematics is also used for odometry -- determining the position of
+ * the robot on the field using encoders and a gyro.
+ */
+class MecanumDriveKinematics {
+ public:
+  /**
+   * Constructs a mecanum drive kinematics object.
+   *
+   * @param frontLeftWheel The location of the front-left wheel relative to the
+   *                       physical center of the robot.
+   * @param frontRightWheel The location of the front-right wheel relative to
+   *                        the physical center of the robot.
+   * @param rearLeftWheel The location of the rear-left wheel relative to the
+   *                      physical center of the robot.
+   * @param rearRightWheel The location of the rear-right wheel relative to the
+   *                       physical center of the robot.
+   */
+  explicit MecanumDriveKinematics(Translation2d frontLeftWheel,
+                                  Translation2d frontRightWheel,
+                                  Translation2d rearLeftWheel,
+                                  Translation2d rearRightWheel)
+      : m_frontLeftWheel{frontLeftWheel},
+        m_frontRightWheel{frontRightWheel},
+        m_rearLeftWheel{rearLeftWheel},
+        m_rearRightWheel{rearRightWheel} {
+    SetInverseKinematics(frontLeftWheel, frontRightWheel, rearLeftWheel,
+                         rearRightWheel);
+    m_forwardKinematics = m_inverseKinematics.householderQr();
+    HAL_Report(HALUsageReporting::kResourceType_Kinematics,
+               HALUsageReporting::kKinematics_MecanumDrive);
+  }
+
+  MecanumDriveKinematics(const MecanumDriveKinematics&) = default;
+
+  /**
+   * Performs inverse kinematics to return the wheel speeds from a desired
+   * chassis velocity. This method is often used to convert joystick values into
+   * wheel speeds.
+   *
+   * This function also supports variable centers of rotation. During normal
+   * operations, the center of rotation is usually the same as the physical
+   * center of the robot; therefore, the argument is defaulted to that use case.
+   * However, if you wish to change the center of rotation for evasive
+   * manuevers, vision alignment, or for any other use case, you can do so.
+   *
+   * @param chassisSpeeds The desired chassis speed.
+   * @param centerOfRotation The center of rotation. For example, if you set the
+   *                         center of rotation at one corner of the robot and
+   *                         provide a chassis speed that only has a dtheta
+   *                         component, the robot will rotate around that
+   *                         corner.
+   *
+   * @return The wheel speeds. Use caution because they are not normalized.
+   *         Sometimes, a user input may cause one of the wheel speeds to go
+   *         above the attainable max velocity. Use the
+   *         MecanumDriveWheelSpeeds::Normalize() function to rectify this
+   *         issue. In addition, you can leverage the power of C++17 to directly
+   *         assign the wheel speeds to variables:
+   *
+   * @code{.cpp}
+   * auto [fl, fr, bl, br] = kinematics.ToWheelSpeeds(chassisSpeeds);
+   * @endcode
+   */
+  MecanumDriveWheelSpeeds ToWheelSpeeds(
+      const ChassisSpeeds& chassisSpeeds,
+      const Translation2d& centerOfRotation = Translation2d());
+
+  /**
+   * Performs forward kinematics to return the resulting chassis state from the
+   * given wheel speeds. This method is often used for odometry -- determining
+   * the robot's position on the field using data from the real-world speed of
+   * each wheel on the robot.
+   *
+   * @param wheelSpeeds The current mecanum drive wheel speeds.
+   *
+   * @return The resulting chassis speed.
+   */
+  ChassisSpeeds ToChassisSpeeds(const MecanumDriveWheelSpeeds& wheelSpeeds);
+
+ private:
+  Eigen::Matrix<double, 4, 3> m_inverseKinematics;
+  Eigen::HouseholderQR<Eigen::Matrix<double, 4, 3>> m_forwardKinematics;
+  Translation2d m_frontLeftWheel;
+  Translation2d m_frontRightWheel;
+  Translation2d m_rearLeftWheel;
+  Translation2d m_rearRightWheel;
+
+  Translation2d m_previousCoR;
+
+  /**
+   * Construct inverse kinematics matrix from wheel locations.
+   *
+   * @param fl The location of the front-left wheel relative to the physical
+   *           center of the robot.
+   * @param fr The location of the front-right wheel relative to the physical
+   *           center of the robot.
+   * @param rl The location of the rear-left wheel relative to the physical
+   *           center of the robot.
+   * @param rr The location of the rear-right wheel relative to the physical
+   *           center of the robot.
+   */
+  void SetInverseKinematics(Translation2d fl, Translation2d fr,
+                            Translation2d rl, Translation2d rr);
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/kinematics/MecanumDriveOdometry.h b/wpilibc/src/main/native/include/frc/kinematics/MecanumDriveOdometry.h
new file mode 100644
index 0000000..697a6b0
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/kinematics/MecanumDriveOdometry.h
@@ -0,0 +1,108 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+
+#include "frc/geometry/Pose2d.h"
+#include "frc/kinematics/MecanumDriveKinematics.h"
+#include "frc/kinematics/MecanumDriveWheelSpeeds.h"
+#include "frc2/Timer.h"
+
+namespace frc {
+
+/**
+ * Class for mecanum drive odometry. Odometry allows you to track the robot's
+ * position on the field over a course of a match using readings from your
+ * mecanum wheel encoders.
+ *
+ * Teams can use odometry during the autonomous period for complex tasks like
+ * path following. Furthermore, odometry can be used for latency compensation
+ * when using computer-vision systems.
+ */
+class MecanumDriveOdometry {
+ public:
+  /**
+   * Constructs a MecanumDriveOdometry object.
+   *
+   * @param kinematics The mecanum drive kinematics for your drivetrain.
+   * @param gyroAngle The angle reported by the gyroscope.
+   * @param initialPose The starting position of the robot on the field.
+   */
+  explicit MecanumDriveOdometry(MecanumDriveKinematics kinematics,
+                                const Rotation2d& gyroAngle,
+                                const Pose2d& initialPose = Pose2d());
+
+  /**
+   * Resets the robot's position on the field.
+   *
+   * The gyroscope angle does not need to be reset here on the user's robot
+   * code. The library automatically takes care of offsetting the gyro angle.
+   *
+   * @param pose The position on the field that your robot is at.
+   * @param gyroAngle The angle reported by the gyroscope.
+   */
+  void ResetPosition(const Pose2d& pose, const Rotation2d& gyroAngle) {
+    m_pose = pose;
+    m_previousAngle = pose.Rotation();
+    m_gyroOffset = m_pose.Rotation() - gyroAngle;
+  }
+
+  /**
+   * Returns the position of the robot on the field.
+   * @return The pose of the robot.
+   */
+  const Pose2d& GetPose() const { return m_pose; }
+
+  /**
+   * Updates the robot's position on the field using forward kinematics and
+   * integration of the pose over time. This method takes in the current time as
+   * a parameter to calculate period (difference between two timestamps). The
+   * period is used to calculate the change in distance from a velocity. This
+   * also takes in an angle parameter which is used instead of the
+   * angular rate that is calculated from forward kinematics.
+   *
+   * @param currentTime The current time.
+   * @param gyroAngle The angle reported by the gyroscope.
+   * @param wheelSpeeds The current wheel speeds.
+   *
+   * @return The new pose of the robot.
+   */
+  const Pose2d& UpdateWithTime(units::second_t currentTime,
+                               const Rotation2d& gyroAngle,
+                               MecanumDriveWheelSpeeds wheelSpeeds);
+
+  /**
+   * Updates the robot's position on the field using forward kinematics and
+   * integration of the pose over time. This method automatically calculates
+   * the current time to calculate period (difference between two timestamps).
+   * The period is used to calculate the change in distance from a velocity.
+   * This also takes in an angle parameter which is used instead of the
+   * angular rate that is calculated from forward kinematics.
+   *
+   * @param gyroAngle The angle reported by the gyroscope.
+   * @param wheelSpeeds The current wheel speeds.
+   *
+   * @return The new pose of the robot.
+   */
+  const Pose2d& Update(const Rotation2d& gyroAngle,
+                       MecanumDriveWheelSpeeds wheelSpeeds) {
+    return UpdateWithTime(frc2::Timer::GetFPGATimestamp(), gyroAngle,
+                          wheelSpeeds);
+  }
+
+ private:
+  MecanumDriveKinematics m_kinematics;
+  Pose2d m_pose;
+
+  units::second_t m_previousTime = -1_s;
+  Rotation2d m_previousAngle;
+  Rotation2d m_gyroOffset;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/kinematics/MecanumDriveWheelSpeeds.h b/wpilibc/src/main/native/include/frc/kinematics/MecanumDriveWheelSpeeds.h
new file mode 100644
index 0000000..159f7f0
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/kinematics/MecanumDriveWheelSpeeds.h
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+
+namespace frc {
+/**
+ * Represents the wheel speeds for a mecanum drive drivetrain.
+ */
+struct MecanumDriveWheelSpeeds {
+  /**
+   * Speed of the front-left wheel.
+   */
+  units::meters_per_second_t frontLeft = 0_mps;
+
+  /**
+   * Speed of the front-right wheel.
+   */
+  units::meters_per_second_t frontRight = 0_mps;
+
+  /**
+   * Speed of the rear-left wheel.
+   */
+  units::meters_per_second_t rearLeft = 0_mps;
+
+  /**
+   * Speed of the rear-right wheel.
+   */
+  units::meters_per_second_t rearRight = 0_mps;
+
+  /**
+   * Normalizes the wheel speeds using some max attainable speed. Sometimes,
+   * after inverse kinematics, the requested speed from a/several modules may be
+   * above the max attainable speed for the driving motor on that module. To fix
+   * this issue, one can "normalize" all the wheel speeds to make sure that all
+   * requested module speeds are below the absolute threshold, while maintaining
+   * the ratio of speeds between modules.
+   *
+   * @param attainableMaxSpeed The absolute max speed that a wheel can reach.
+   */
+  void Normalize(units::meters_per_second_t attainableMaxSpeed);
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h b/wpilibc/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h
new file mode 100644
index 0000000..f889363
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h
@@ -0,0 +1,170 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <array>
+#include <cstddef>
+
+#include <Eigen/Core>
+#include <Eigen/QR>
+#include <hal/FRCUsageReporting.h>
+#include <units/units.h>
+
+#include "frc/geometry/Rotation2d.h"
+#include "frc/geometry/Translation2d.h"
+#include "frc/kinematics/ChassisSpeeds.h"
+#include "frc/kinematics/SwerveModuleState.h"
+
+namespace frc {
+/**
+ * Helper class that converts a chassis velocity (dx, dy, and dtheta components)
+ * into individual module states (speed and angle).
+ *
+ * The inverse kinematics (converting from a desired chassis velocity to
+ * individual module states) uses the relative locations of the modules with
+ * respect to the center of rotation. The center of rotation for inverse
+ * kinematics is also variable. This means that you can set your set your center
+ * of rotation in a corner of the robot to perform special evasion manuevers.
+ *
+ * Forward kinematics (converting an array of module states into the overall
+ * chassis motion) is performs the exact opposite of what inverse kinematics
+ * does. Since this is an overdetermined system (more equations than variables),
+ * we use a least-squares approximation.
+ *
+ * The inverse kinematics: [moduleStates] = [moduleLocations] * [chassisSpeeds]
+ * We take the Moore-Penrose pseudoinverse of [moduleLocations] and then
+ * multiply by [moduleStates] to get our chassis speeds.
+ *
+ * Forward kinematics is also used for odometry -- determining the position of
+ * the robot on the field using encoders and a gyro.
+ */
+template <size_t NumModules>
+class SwerveDriveKinematics {
+ public:
+  /**
+   * Constructs a swerve drive kinematics object. This takes in a variable
+   * number of wheel locations as Translation2ds. The order in which you pass in
+   * the wheel locations is the same order that you will recieve the module
+   * states when performing inverse kinematics. It is also expected that you
+   * pass in the module states in the same order when calling the forward
+   * kinematics methods.
+   *
+   * @param wheels The locations of the wheels relative to the physical center
+   * of the robot.
+   */
+  template <typename... Wheels>
+  explicit SwerveDriveKinematics(Translation2d wheel, Wheels&&... wheels)
+      : m_modules{wheel, wheels...} {
+    static_assert(sizeof...(wheels) >= 1,
+                  "A swerve drive requires at least two modules");
+
+    for (size_t i = 0; i < NumModules; i++) {
+      // clang-format off
+      m_inverseKinematics.template block<2, 3>(i * 2, 0) <<
+        1, 0, (-m_modules[i].Y()).template to<double>(),
+        0, 1, (+m_modules[i].X()).template to<double>();
+      // clang-format on
+    }
+
+    m_forwardKinematics = m_inverseKinematics.householderQr();
+
+    HAL_Report(HALUsageReporting::kResourceType_Kinematics,
+               HALUsageReporting::kKinematics_SwerveDrive);
+  }
+
+  SwerveDriveKinematics(const SwerveDriveKinematics&) = default;
+
+  /**
+   * Performs inverse kinematics to return the module states from a desired
+   * chassis velocity. This method is often used to convert joystick values into
+   * module speeds and angles.
+   *
+   * This function also supports variable centers of rotation. During normal
+   * operations, the center of rotation is usually the same as the physical
+   * center of the robot; therefore, the argument is defaulted to that use case.
+   * However, if you wish to change the center of rotation for evasive
+   * manuevers, vision alignment, or for any other use case, you can do so.
+   *
+   * @param chassisSpeeds The desired chassis speed.
+   * @param centerOfRotation The center of rotation. For example, if you set the
+   * center of rotation at one corner of the robot and provide a chassis speed
+   * that only has a dtheta component, the robot will rotate around that corner.
+   *
+   * @return An array containing the module states. Use caution because these
+   * module states are not normalized. Sometimes, a user input may cause one of
+   * the module speeds to go above the attainable max velocity. Use the
+   * <NormalizeWheelSpeeds> function to rectify this issue. In addition, you can
+   * leverage the power of C++17 to directly assign the module states to
+   * variables:
+   *
+   * @code{.cpp}
+   * auto [fl, fr, bl, br] = kinematics.ToSwerveModuleStates(chassisSpeeds);
+   * @endcode
+   */
+  std::array<SwerveModuleState, NumModules> ToSwerveModuleStates(
+      const ChassisSpeeds& chassisSpeeds,
+      const Translation2d& centerOfRotation = Translation2d());
+
+  /**
+   * Performs forward kinematics to return the resulting chassis state from the
+   * given module states. This method is often used for odometry -- determining
+   * the robot's position on the field using data from the real-world speed and
+   * angle of each module on the robot.
+   *
+   * @param wheelStates The state of the modules (as a SwerveModuleState type)
+   * as measured from respective encoders and gyros. The order of the swerve
+   * module states should be same as passed into the constructor of this class.
+   *
+   * @return The resulting chassis speed.
+   */
+  template <typename... ModuleStates>
+  ChassisSpeeds ToChassisSpeeds(ModuleStates&&... wheelStates);
+
+  /**
+   * Performs forward kinematics to return the resulting chassis state from the
+   * given module states. This method is often used for odometry -- determining
+   * the robot's position on the field using data from the real-world speed and
+   * angle of each module on the robot.
+   *
+   * @param moduleStates The state of the modules as an std::array of type
+   * SwerveModuleState, NumModules long as measured from respective encoders
+   * and gyros. The order of the swerve module states should be same as passed
+   * into the constructor of this class.
+   *
+   * @return The resulting chassis speed.
+   */
+  ChassisSpeeds ToChassisSpeeds(
+      std::array<SwerveModuleState, NumModules> moduleStates);
+
+  /**
+   * Normalizes the wheel speeds using some max attainable speed. Sometimes,
+   * after inverse kinematics, the requested speed from a/several modules may be
+   * above the max attainable speed for the driving motor on that module. To fix
+   * this issue, one can "normalize" all the wheel speeds to make sure that all
+   * requested module speeds are below the absolute threshold, while maintaining
+   * the ratio of speeds between modules.
+   *
+   * @param moduleStates Reference to array of module states. The array will be
+   * mutated with the normalized speeds!
+   * @param attainableMaxSpeed The absolute max speed that a module can reach.
+   */
+  static void NormalizeWheelSpeeds(
+      std::array<SwerveModuleState, NumModules>* moduleStates,
+      units::meters_per_second_t attainableMaxSpeed);
+
+ private:
+  Eigen::Matrix<double, NumModules * 2, 3> m_inverseKinematics;
+  Eigen::HouseholderQR<Eigen::Matrix<double, NumModules * 2, 3>>
+      m_forwardKinematics;
+  std::array<Translation2d, NumModules> m_modules;
+
+  Translation2d m_previousCoR;
+};
+}  // namespace frc
+
+#include "SwerveDriveKinematics.inc"
diff --git a/wpilibc/src/main/native/include/frc/kinematics/SwerveDriveKinematics.inc b/wpilibc/src/main/native/include/frc/kinematics/SwerveDriveKinematics.inc
new file mode 100644
index 0000000..b362aa0
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/kinematics/SwerveDriveKinematics.inc
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared 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... Wheels>
+SwerveDriveKinematics(Translation2d, Wheels...)
+    ->SwerveDriveKinematics<1 + sizeof...(Wheels)>;
+
+template <size_t NumModules>
+std::array<SwerveModuleState, NumModules>
+SwerveDriveKinematics<NumModules>::ToSwerveModuleStates(
+    const ChassisSpeeds& chassisSpeeds, const Translation2d& centerOfRotation) {
+  // We have a new center of rotation. We need to compute the matrix again.
+  if (centerOfRotation != m_previousCoR) {
+    for (size_t i = 0; i < NumModules; i++) {
+      // clang-format off
+      m_inverseKinematics.template block<2, 3>(i * 2, 0) <<
+        1, 0, (-m_modules[i].Y() + centerOfRotation.Y()).template to<double>(),
+        0, 1, (+m_modules[i].X() - centerOfRotation.X()).template to<double>();
+      // clang-format on
+    }
+    m_previousCoR = centerOfRotation;
+  }
+
+  Eigen::Vector3d chassisSpeedsVector;
+  chassisSpeedsVector << chassisSpeeds.vx.to<double>(),
+      chassisSpeeds.vy.to<double>(), chassisSpeeds.omega.to<double>();
+
+  Eigen::Matrix<double, NumModules * 2, 1> moduleStatesMatrix =
+      m_inverseKinematics * chassisSpeedsVector;
+  std::array<SwerveModuleState, NumModules> moduleStates;
+
+  for (size_t i = 0; i < NumModules; i++) {
+    units::meters_per_second_t x =
+        units::meters_per_second_t{moduleStatesMatrix(i * 2, 0)};
+    units::meters_per_second_t y =
+        units::meters_per_second_t{moduleStatesMatrix(i * 2 + 1, 0)};
+
+    auto speed = units::math::hypot(x, y);
+    Rotation2d rotation{x.to<double>(), y.to<double>()};
+
+    moduleStates[i] = {speed, rotation};
+  }
+
+  return moduleStates;
+}
+
+template <size_t NumModules>
+template <typename... ModuleStates>
+ChassisSpeeds SwerveDriveKinematics<NumModules>::ToChassisSpeeds(
+    ModuleStates&&... wheelStates) {
+  static_assert(sizeof...(wheelStates) == NumModules,
+                "Number of modules is not consistent with number of wheel "
+                "locations provided in constructor.");
+
+  std::array<SwerveModuleState, NumModules> moduleStates{wheelStates...};
+
+  return this->ToChassisSpeeds(moduleStates);
+}
+
+template <size_t NumModules>
+ChassisSpeeds SwerveDriveKinematics<NumModules>::ToChassisSpeeds(
+    std::array<SwerveModuleState, NumModules> moduleStates) {
+  Eigen::Matrix<double, NumModules * 2, 1> moduleStatesMatrix;
+
+  for (size_t i = 0; i < NumModules; i++) {
+    SwerveModuleState module = moduleStates[i];
+    moduleStatesMatrix.row(i * 2)
+        << module.speed.to<double>() * module.angle.Cos();
+    moduleStatesMatrix.row(i * 2 + 1)
+        << module.speed.to<double>() * module.angle.Sin();
+  }
+
+  Eigen::Vector3d chassisSpeedsVector =
+      m_forwardKinematics.solve(moduleStatesMatrix);
+
+  return {units::meters_per_second_t{chassisSpeedsVector(0)},
+          units::meters_per_second_t{chassisSpeedsVector(1)},
+          units::radians_per_second_t{chassisSpeedsVector(2)}};
+}
+
+template <size_t NumModules>
+void SwerveDriveKinematics<NumModules>::NormalizeWheelSpeeds(
+    std::array<SwerveModuleState, NumModules>* moduleStates,
+    units::meters_per_second_t attainableMaxSpeed) {
+  auto& states = *moduleStates;
+  auto realMaxSpeed = std::max_element(states.begin(), states.end(),
+                                       [](const auto& a, const auto& b) {
+                                         return units::math::abs(a.speed) <
+                                                units::math::abs(b.speed);
+                                       })
+                          ->speed;
+
+  if (realMaxSpeed > attainableMaxSpeed) {
+    for (auto& module : states) {
+      module.speed = module.speed / realMaxSpeed * attainableMaxSpeed;
+    }
+  }
+}
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/kinematics/SwerveDriveOdometry.h b/wpilibc/src/main/native/include/frc/kinematics/SwerveDriveOdometry.h
new file mode 100644
index 0000000..8093ca5
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/kinematics/SwerveDriveOdometry.h
@@ -0,0 +1,121 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <chrono>
+#include <cstddef>
+#include <ctime>
+
+#include <units/units.h>
+
+#include "SwerveDriveKinematics.h"
+#include "SwerveModuleState.h"
+#include "frc/geometry/Pose2d.h"
+#include "frc2/Timer.h"
+
+namespace frc {
+
+/**
+ * Class for swerve drive odometry. Odometry allows you to track the robot's
+ * position on the field over a course of a match using readings from your
+ * swerve drive encoders and swerve azimuth encoders.
+ *
+ * Teams can use odometry during the autonomous period for complex tasks like
+ * path following. Furthermore, odometry can be used for latency compensation
+ * when using computer-vision systems.
+ */
+template <size_t NumModules>
+class SwerveDriveOdometry {
+ public:
+  /**
+   * Constructs a SwerveDriveOdometry object.
+   *
+   * @param kinematics The swerve drive kinematics for your drivetrain.
+   * @param gyroAngle The angle reported by the gyroscope.
+   * @param initialPose The starting position of the robot on the field.
+   */
+  SwerveDriveOdometry(SwerveDriveKinematics<NumModules> kinematics,
+                      const Rotation2d& gyroAngle,
+                      const Pose2d& initialPose = Pose2d());
+
+  /**
+   * Resets the robot's position on the field.
+   *
+   * The gyroscope angle does not need to be reset here on the user's robot
+   * code. The library automatically takes care of offsetting the gyro angle.
+   *
+   * @param pose The position on the field that your robot is at.
+   * @param gyroAngle The angle reported by the gyroscope.
+   */
+  void ResetPosition(const Pose2d& pose, const Rotation2d& gyroAngle) {
+    m_pose = pose;
+    m_previousAngle = pose.Rotation();
+    m_gyroOffset = m_pose.Rotation() - gyroAngle;
+  }
+
+  /**
+   * Returns the position of the robot on the field.
+   * @return The pose of the robot.
+   */
+  const Pose2d& GetPose() const { return m_pose; }
+
+  /**
+   * Updates the robot's position on the field using forward kinematics and
+   * integration of the pose over time. This method takes in the current time as
+   * a parameter to calculate period (difference between two timestamps). The
+   * period is used to calculate the change in distance from a velocity. This
+   * also takes in an angle parameter which is used instead of the
+   * angular rate that is calculated from forward kinematics.
+   *
+   * @param currentTime The current time.
+   * @param gyroAngle The angle reported by the gyroscope.
+   * @param moduleStates The current state of all swerve modules. Please provide
+   *                     the states in the same order in which you instantiated
+   *                     your SwerveDriveKinematics.
+   *
+   * @return The new pose of the robot.
+   */
+  template <typename... ModuleStates>
+  const Pose2d& UpdateWithTime(units::second_t currentTime,
+                               const Rotation2d& gyroAngle,
+                               ModuleStates&&... moduleStates);
+
+  /**
+   * Updates the robot's position on the field using forward kinematics and
+   * integration of the pose over time. This method automatically calculates
+   * the current time to calculate period (difference between two timestamps).
+   * The period is used to calculate the change in distance from a velocity.
+   * This also takes in an angle parameter which is used instead of the
+   * angular rate that is calculated from forward kinematics.
+   *
+   * @param gyroAngle The angle reported by the gyroscope.
+   * @param moduleStates The current state of all swerve modules. Please provide
+   *                     the states in the same order in which you instantiated
+   *                     your SwerveDriveKinematics.
+   *
+   * @return The new pose of the robot.
+   */
+  template <typename... ModuleStates>
+  const Pose2d& Update(const Rotation2d& gyroAngle,
+                       ModuleStates&&... moduleStates) {
+    return UpdateWithTime(frc2::Timer::GetFPGATimestamp(), gyroAngle,
+                          moduleStates...);
+  }
+
+ private:
+  SwerveDriveKinematics<NumModules> m_kinematics;
+  Pose2d m_pose;
+
+  units::second_t m_previousTime = -1_s;
+  Rotation2d m_previousAngle;
+  Rotation2d m_gyroOffset;
+};
+
+}  // namespace frc
+
+#include "SwerveDriveOdometry.inc"
diff --git a/wpilibc/src/main/native/include/frc/kinematics/SwerveDriveOdometry.inc b/wpilibc/src/main/native/include/frc/kinematics/SwerveDriveOdometry.inc
new file mode 100644
index 0000000..e794388
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/kinematics/SwerveDriveOdometry.inc
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared 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/FRCUsageReporting.h>
+
+namespace frc {
+template <size_t NumModules>
+SwerveDriveOdometry<NumModules>::SwerveDriveOdometry(
+    SwerveDriveKinematics<NumModules> kinematics, const Rotation2d& gyroAngle,
+    const Pose2d& initialPose)
+    : m_kinematics(kinematics), m_pose(initialPose) {
+  m_previousAngle = m_pose.Rotation();
+  m_gyroOffset = m_pose.Rotation() - gyroAngle;
+  HAL_Report(HALUsageReporting::kResourceType_Odometry,
+             HALUsageReporting::kOdometry_SwerveDrive);
+}
+
+template <size_t NumModules>
+template <typename... ModuleStates>
+const Pose2d& frc::SwerveDriveOdometry<NumModules>::UpdateWithTime(
+    units::second_t currentTime, const Rotation2d& gyroAngle,
+    ModuleStates&&... moduleStates) {
+  units::second_t deltaTime =
+      (m_previousTime >= 0_s) ? currentTime - m_previousTime : 0_s;
+  m_previousTime = currentTime;
+
+  auto angle = gyroAngle + m_gyroOffset;
+
+  auto [dx, dy, dtheta] = m_kinematics.ToChassisSpeeds(moduleStates...);
+  static_cast<void>(dtheta);
+
+  auto newPose = m_pose.Exp(
+      {dx * deltaTime, dy * deltaTime, (angle - m_previousAngle).Radians()});
+
+  m_previousAngle = angle;
+  m_pose = {newPose.Translation(), angle};
+
+  return m_pose;
+}
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/kinematics/SwerveModuleState.h b/wpilibc/src/main/native/include/frc/kinematics/SwerveModuleState.h
new file mode 100644
index 0000000..fbfe0d1
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/kinematics/SwerveModuleState.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+
+#include "frc/geometry/Rotation2d.h"
+
+namespace frc {
+/**
+ * Represents the state of one swerve module.
+ */
+struct SwerveModuleState {
+  /**
+   * Speed of the wheel of the module.
+   */
+  units::meters_per_second_t speed = 0_mps;
+
+  /**
+   * Angle of the module.
+   */
+  Rotation2d angle;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h b/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h
new file mode 100644
index 0000000..c7e0ec2
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2012-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared 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 Sendable;
+
+/**
+ * The LiveWindow class is the public interface for putting sensors and
+ * actuators on the LiveWindow.
+ */
+class LiveWindow {
+ public:
+  LiveWindow(const LiveWindow&) = delete;
+  LiveWindow& operator=(const LiveWindow&) = delete;
+
+  /**
+   * Get an instance of the LiveWindow main class.
+   *
+   * This is a singleton to guarantee that there is only a single instance
+   * regardless of how many times GetInstance is called.
+   */
+  static LiveWindow* GetInstance();
+
+  /**
+   * Enable telemetry for a single component.
+   *
+   * @param sendable component
+   */
+  void EnableTelemetry(Sendable* component);
+
+  /**
+   * Disable telemetry for a single component.
+   *
+   * @param sendable component
+   */
+  void DisableTelemetry(Sendable* component);
+
+  /**
+   * Disable ALL telemetry.
+   */
+  void DisableAllTelemetry();
+
+  bool IsEnabled() const;
+
+  /**
+   * Change the enabled status of LiveWindow.
+   *
+   * If it changes to enabled, start livewindow running otherwise stop it
+   */
+  void SetEnabled(bool enabled);
+
+  /**
+   * Tell all the sensors to update (send) their values.
+   *
+   * Actuators are handled through callbacks on their value changing from the
+   * SmartDashboard widgets.
+   */
+  void UpdateValues();
+
+ private:
+  LiveWindow();
+
+  struct Impl;
+  std::unique_ptr<Impl> m_impl;
+
+  /**
+   * Updates the entries, without using a mutex or lock.
+   */
+  void UpdateValuesUnsafe();
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInLayouts.h b/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInLayouts.h
new file mode 100644
index 0000000..1d1ea5f
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInLayouts.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/shuffleboard/LayoutType.h"
+
+namespace frc {
+
+/**
+ * The types of layouts bundled with Shuffleboard.
+ *
+ * <pre>{@code
+ * ShuffleboardLayout myList = Shuffleboard::GetTab("My Tab")
+ *   .GetLayout(BuiltinLayouts::kList, "My List");
+ * }</pre>
+ */
+enum class BuiltInLayouts {
+  /**
+   * Groups components in a vertical list. New widgets added to the layout will
+   * be placed at the bottom of the list. <br>Custom properties: <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Label position</td><td>String</td><td>"BOTTOM"</td>
+   * <td>The position of component labels inside the grid. One of
+   * {@code ["TOP", "LEFT", "BOTTOM", "RIGHT", "HIDDEN"}</td></tr>
+   * </table>
+   */
+  kList,
+
+  /**
+   * Groups components in an <i>n</i> x <i>m</i> grid. Grid layouts default to
+   * 3x3. <br>Custom properties: <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Number of columns</td><td>Number</td><td>3</td><td>Must be in the
+   * range [1,15]</td>
+   * </tr>
+   * <tr><td>Number of rows</td><td>Number</td><td>3</td><td>Must be in the
+   * range [1,15]</td></tr> <tr> <td>Label position</td> <td>String</td>
+   * <td>"BOTTOM"</td>
+   * <td>The position of component labels inside the grid.
+   * One of {@code ["TOP", "LEFT", "BOTTOM", "RIGHT", "HIDDEN"}</td>
+   * </tr>
+   * </table>
+   */
+  kGrid
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInWidgets.h b/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInWidgets.h
new file mode 100644
index 0000000..8e666b7
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInWidgets.h
@@ -0,0 +1,386 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/shuffleboard/WidgetType.h"
+
+namespace frc {
+
+/**
+ * The types of the widgets bundled with Shuffleboard.
+ *
+ * <p>For example, setting a number to be displayed with a slider:
+ * <pre>{@code
+ * NetworkTableEntry example = Shuffleboard.getTab("My Tab")
+ *   .add("My Number", 0)
+ *   .withWidget(BuiltInWidgets.kNumberSlider)
+ *   .getEntry();
+ * }</pre>
+ *
+ * <p>Each value in this enum goes into detail on what data types that widget
+ * can support, as well as the custom properties that widget uses.
+ */
+enum class BuiltInWidgets {
+  /**
+   * Displays a value with a simple text field.
+   * <br>Supported types:
+   * <ul>
+   * <li>String</li>
+   * <li>Number</li>
+   * <li>Boolean</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kTextView,
+  /**
+   * Displays a number with a controllable slider.
+   * <br>Supported types:
+   * <ul>
+   * <li>Number</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>-1.0</td><td>The minimum value of the
+   * slider</td></tr> <tr><td>Max</td><td>Number</td><td>1.0</td><td>The maximum
+   * value of the slider</td></tr> <tr><td>Block
+   * increment</td><td>Number</td><td>0.0625</td> <td>How much to move the
+   * slider by with the arrow keys</td></tr>
+   * </table>
+   */
+  kNumberSlider,
+  /**
+   * Displays a number with a view-only bar.
+   * <br>Supported types:
+   * <ul>
+   * <li>Number</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>-1.0</td><td>The minimum value of the
+   * bar</td></tr> <tr><td>Max</td><td>Number</td><td>1.0</td><td>The maximum
+   * value of the bar</td></tr>
+   * <tr><td>Center</td><td>Number</td><td>0</td><td>The center ("zero") value
+   * of the bar</td></tr>
+   * </table>
+   */
+  kNumberBar,
+  /**
+   * Displays a number with a view-only dial. Displayed values are rounded to
+   * the nearest integer. <br>Supported types: <ul> <li>Number</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>0</td><td>The minimum value of the
+   * dial</td></tr> <tr><td>Max</td><td>Number</td><td>100</td><td>The maximum
+   * value of the dial</td></tr> <tr><td>Show
+   * value</td><td>Boolean</td><td>true</td> <td>Whether or not to show the
+   * value as text</td></tr>
+   * </table>
+   */
+  kDial,
+  /**
+   * Displays a number with a graph. <strong>NOTE:</strong> graphs can be taxing
+   * on the computer running the dashboard. Keep the number of visible data
+   * points to a minimum. Making the widget smaller also helps with performance,
+   * but may cause the graph to become difficult to read. <br>Supported types:
+   * <ul>
+   * <li>Number</li>
+   * <li>Number array</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Visible time</td><td>Number</td><td>30</td>
+   * <td>How long, in seconds, should past data be visible for</td></tr>
+   * </table>
+   */
+  kGraph,
+  /**
+   * Displays a boolean value as a large colored box.
+   * <br>Supported types:
+   * <ul>
+   * <li>Boolean</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Color when true</td><td>Color</td><td>"green"</td>
+   * <td>Can be specified as a string ({@code "#00FF00"}) or a rgba integer
+   * ({@code 0x00FF0000})
+   * </td></tr>
+   * <tr><td>Color when false</td><td>Color</td><td>"red"</td>
+   * <td>Can be specified as a string or a number</td></tr>
+   * </table>
+   */
+  kBooleanBox,
+  /**
+   * Displays a boolean with a large interactive toggle button.
+   * <br>Supported types:
+   * <ul>
+   * <li>Boolean</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kToggleButton,
+  /**
+   * Displays a boolean with a fixed-size toggle switch.
+   * <br>Supported types:
+   * <ul>
+   * <li>Boolean</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kToggleSwitch,
+  /**
+   * Displays an analog input or a raw number with a number bar.
+   * <br>Supported types:
+   * <ul>
+   * <li>Number</li>
+   * <li>{@link edu.wpi.first.wpilibj.AnalogInput}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>0</td><td>The minimum value of the
+   * bar</td></tr> <tr><td>Max</td><td>Number</td><td>5</td><td>The maximum
+   * value of the bar</td></tr>
+   * <tr><td>Center</td><td>Number</td><td>0</td><td>The center ("zero") value
+   * of the bar</td></tr>
+   * <tr><td>Orientation</td><td>String</td><td>"HORIZONTAL"</td>
+   * <td>The orientation of the bar. One of {@code ["HORIZONTAL",
+   * "VERTICAL"]}</td></tr> <tr><td>Number of tick
+   * marks</td><td>Number</td><td>5</td> <td>The number of discrete ticks on the
+   * bar</td></tr>
+   * </table>
+   */
+  kVoltageView,
+  /**
+   * Displays a {@link edu.wpi.first.wpilibj.PowerDistributionPanel
+   * PowerDistributionPanel}. <br>Supported types: <ul> <li>{@link
+   * edu.wpi.first.wpilibj.PowerDistributionPanel}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Show voltage and current values</td><td>Boolean</td><td>true</td>
+   * <td>Whether or not to display the voltage and current draw</td></tr>
+   * </table>
+   */
+  kPowerDistributionPanel,
+  /**
+   * Displays a {@link edu.wpi.first.wpilibj.smartdashboard.SendableChooser
+   * SendableChooser} with a dropdown combo box with a list of options.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.smartdashboard.SendableChooser}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kComboBoxChooser,
+  /**
+   * Displays a {@link edu.wpi.first.wpilibj.smartdashboard.SendableChooser
+   * SendableChooser} with a toggle button for each available option.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.smartdashboard.SendableChooser}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kSplitButtonChooser,
+  /**
+   * Displays an {@link edu.wpi.first.wpilibj.Encoder} displaying its speed,
+   * total travelled distance, and its distance per tick. <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.Encoder}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kEncoder,
+  /**
+   * Displays a {@link edu.wpi.first.wpilibj.SpeedController SpeedController}.
+   * The speed controller will be controllable from the dashboard when test mode
+   * is enabled, but will otherwise be view-only. <br>Supported types: <ul>
+   * <li>{@link edu.wpi.first.wpilibj.PWMSpeedController}</li>
+   * <li>{@link edu.wpi.first.wpilibj.DMC60}</li>
+   * <li>{@link edu.wpi.first.wpilibj.Jaguar}</li>
+   * <li>{@link edu.wpi.first.wpilibj.PWMTalonSRX}</li>
+   * <li>{@link edu.wpi.first.wpilibj.PWMVictorSPX}</li>
+   * <li>{@link edu.wpi.first.wpilibj.SD540}</li>
+   * <li>{@link edu.wpi.first.wpilibj.Spark}</li>
+   * <li>{@link edu.wpi.first.wpilibj.Talon}</li>
+   * <li>{@link edu.wpi.first.wpilibj.Victor}</li>
+   * <li>{@link edu.wpi.first.wpilibj.VictorSP}</li>
+   * <li>{@link edu.wpi.first.wpilibj.SpeedControllerGroup}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Orientation</td><td>String</td><td>"HORIZONTAL"</td>
+   * <td>One of {@code ["HORIZONTAL", "VERTICAL"]}</td></tr>
+   * </table>
+   */
+  kSpeedController,
+  /**
+   * Displays a command with a toggle button. Pressing the button will start the
+   * command, and the button will automatically release when the command
+   * completes. <br>Supported types: <ul> <li>{@link
+   * edu.wpi.first.wpilibj.command.Command}</li> <li>{@link
+   * edu.wpi.first.wpilibj.command.CommandGroup}</li> <li>Any custom subclass of
+   * {@code Command} or {@code CommandGroup}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kCommand,
+  /**
+   * Displays a PID command with a checkbox and an editor for the PIDF
+   * constants. Selecting the checkbox will start the command, and the checkbox
+   * will automatically deselect when the command completes. <br>Supported
+   * types: <ul> <li>{@link edu.wpi.first.wpilibj.command.PIDCommand}</li>
+   * <li>Any custom subclass of {@code PIDCommand}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kPIDCommand,
+  /**
+   * Displays a PID controller with an editor for the PIDF constants and a
+   * toggle switch for enabling and disabling the controller. <br>Supported
+   * types: <ul> <li>{@link edu.wpi.first.wpilibj.PIDController}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kPIDController,
+  /**
+   * Displays an accelerometer with a number bar displaying the magnitude of the
+   * acceleration and text displaying the exact value. <br>Supported types: <ul>
+   * <li>{@link edu.wpi.first.wpilibj.AnalogAccelerometer}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>-1</td>
+   * <td>The minimum acceleration value to display</td></tr>
+   * <tr><td>Max</td><td>Number</td><td>1</td>
+   * <td>The maximum acceleration value to display</td></tr>
+   * <tr><td>Show text</td><td>Boolean</td><td>true</td>
+   * <td>Show or hide the acceleration values</td></tr>
+   * <tr><td>Precision</td><td>Number</td><td>2</td>
+   * <td>How many numbers to display after the decimal point</td></tr>
+   * <tr><td>Show tick marks</td><td>Boolean</td><td>false</td>
+   * <td>Show or hide the tick marks on the number bars</td></tr>
+   * </table>
+   */
+  kAccelerometer,
+  /**
+   * Displays a 3-axis accelerometer with a number bar for each axis'
+   * accleration. <br>Supported types: <ul> <li>{@link
+   * edu.wpi.first.wpilibj.ADXL345_I2C}</li> <li>{@link
+   * edu.wpi.first.wpilibj.ADXL345_SPI}</li> <li>{@link
+   * edu.wpi.first.wpilibj.ADXL362}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Range</td><td>{@link Range}</td><td>k16G</td><td>The accelerometer
+   * range</td></tr> <tr><td>Show value</td><td>Boolean</td><td>true</td>
+   * <td>Show or hide the acceleration values</td></tr>
+   * <tr><td>Precision</td><td>Number</td><td>2</td>
+   * <td>How many numbers to display after the decimal point</td></tr>
+   * <tr><td>Show tick marks</td><td>Boolean</td><td>false</td>
+   * <td>Show or hide the tick marks on the number bars</td></tr>
+   * </table>
+   */
+  k3AxisAccelerometer,
+  /**
+   * Displays a gyro with a dial from 0 to 360 degrees.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.ADXRS450_Gyro}</li>
+   * <li>{@link edu.wpi.first.wpilibj.AnalogGyro}</li>
+   * <li>Any custom subclass of {@code GyroBase} (such as a MXP gyro)</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Major tick
+   * spacing</td><td>Number</td><td>45</td><td>Degrees</td></tr>
+   * <tr><td>Starting angle</td><td>Number</td><td>180</td>
+   * <td>How far to rotate the entire dial, in degrees</td></tr>
+   * <tr><td>Show tick mark ring</td><td>Boolean</td><td>true</td></tr>
+   * </table>
+   */
+  kGyro,
+  /**
+   * Displays a relay with toggle buttons for each supported mode (off, on,
+   * forward, reverse). <br>Supported types: <ul> <li>{@link
+   * edu.wpi.first.wpilibj.Relay}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kRelay,
+  /**
+   * Displays a differential drive with a widget that displays the speed of each
+   * side of the drivebase and a vector for the direction and rotation of the
+   * drivebase. The widget will be controllable if the robot is in test mode.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.drive.DifferentialDrive}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Number of wheels</td><td>Number</td><td>4</td><td>Must be a
+   * positive even integer
+   * </td></tr>
+   * <tr><td>Wheel diameter</td><td>Number</td><td>80</td><td>Pixels</td></tr>
+   * <tr><td>Show velocity vectors</td><td>Boolean</td><td>true</td></tr>
+   * </table>
+   */
+  kDifferentialDrive,
+  /**
+   * Displays a mecanum drive with a widget that displays the speed of each
+   * wheel, and vectors for the direction and rotation of the drivebase. The
+   * widget will be controllable if the robot is in test mode. <br>Supported
+   * types: <ul> <li>{@link edu.wpi.first.wpilibj.drive.MecanumDrive}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Show velocity vectors</td><td>Boolean</td><td>true</td></tr>
+   * </table>
+   */
+  kMecanumDrive,
+  /**
+   * Displays a camera stream.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.cscore.VideoSource} (as long as it is streaming on an
+   * MJPEG server)</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Show crosshair</td><td>Boolean</td><td>true</td>
+   * <td>Show or hide a crosshair on the image</td></tr>
+   * <tr><td>Crosshair color</td><td>Color</td><td>"white"</td>
+   * <td>Can be a string or a rgba integer</td></tr>
+   * <tr><td>Show controls</td><td>Boolean</td><td>true</td><td>Show or hide the
+   * stream controls
+   * </td></tr>
+   * <tr><td>Rotation</td><td>String</td><td>"NONE"</td>
+   * <td>Rotates the displayed image. One of {@code ["NONE", "QUARTER_CW",
+   * "QUARTER_CCW", "HALF"]}
+   * </td></tr>
+   * </table>
+   */
+  kCameraStream
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ComplexWidget.h b/wpilibc/src/main/native/include/frc/shuffleboard/ComplexWidget.h
new file mode 100644
index 0000000..218ed2f
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/ComplexWidget.h
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <networktables/NetworkTable.h>
+#include <wpi/Twine.h>
+
+#include "frc/shuffleboard/ShuffleboardWidget.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableBuilderImpl.h"
+
+namespace frc {
+
+class Sendable;
+class ShuffleboardContainer;
+
+/**
+ * A Shuffleboard widget that handles a {@link Sendable} object such as a speed
+ * controller or sensor.
+ */
+class ComplexWidget final : public ShuffleboardWidget<ComplexWidget> {
+ public:
+  ComplexWidget(ShuffleboardContainer& parent, const wpi::Twine& title,
+                Sendable& sendable);
+
+  void EnableIfActuator() override;
+
+  void DisableIfActuator() override;
+
+  void BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                 std::shared_ptr<nt::NetworkTable> metaTable) override;
+
+ private:
+  Sendable& m_sendable;
+  SendableBuilderImpl m_builder;
+  bool m_builderInit = false;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/LayoutType.h b/wpilibc/src/main/native/include/frc/shuffleboard/LayoutType.h
new file mode 100644
index 0000000..00a5e36
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/LayoutType.h
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/StringRef.h>
+
+namespace frc {
+
+/**
+ * Represents the type of a layout in Shuffleboard. Using this is preferred over
+ * specifying raw strings, to avoid typos and having to know or look up the
+ * exact string name for a desired layout.
+ *
+ * @see BuiltInLayouts the built-in layout types
+ */
+class LayoutType {
+ public:
+  explicit constexpr LayoutType(const char* layoutName)
+      : m_layoutName(layoutName) {}
+  ~LayoutType() = default;
+
+  /**
+   * Gets the string type of the layout as defined by that layout in
+   * Shuffleboard.
+   */
+  wpi::StringRef GetLayoutName() const;
+
+ private:
+  const char* m_layoutName;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/RecordingController.h b/wpilibc/src/main/native/include/frc/shuffleboard/RecordingController.h
new file mode 100644
index 0000000..dacbdb4
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/RecordingController.h
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringRef.h>
+
+#include "frc/shuffleboard/ShuffleboardEventImportance.h"
+
+namespace frc {
+namespace detail {
+
+class RecordingController final {
+ public:
+  explicit RecordingController(nt::NetworkTableInstance ntInstance);
+  virtual ~RecordingController() = default;
+
+  void StartRecording();
+  void StopRecording();
+  void SetRecordingFileNameFormat(wpi::StringRef format);
+  void ClearRecordingFileNameFormat();
+
+  void AddEventMarker(wpi::StringRef name, wpi::StringRef description,
+                      ShuffleboardEventImportance importance);
+
+ private:
+  nt::NetworkTableEntry m_recordingControlEntry;
+  nt::NetworkTableEntry m_recordingFileNameFormatEntry;
+  std::shared_ptr<nt::NetworkTable> m_eventsTable;
+};
+
+}  // namespace detail
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h b/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h
new file mode 100644
index 0000000..5610cf8
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h
@@ -0,0 +1,95 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+#include <memory>
+#include <string>
+
+#ifndef DYNAMIC_CAMERA_SERVER
+#include <cscore_oo.h>
+#else
+namespace cs {
+class VideoSource;
+}  // namespace cs
+typedef int CS_Handle;
+typedef CS_Handle CS_Source;
+#endif
+
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableCameraWrapper;
+
+namespace detail {
+constexpr const char* kProtocol = "camera_server://";
+std::shared_ptr<SendableCameraWrapper>& GetSendableCameraWrapper(
+    CS_Source source);
+void AddToSendableRegistry(Sendable* sendable, std::string name);
+}  // namespace detail
+
+/**
+ * A wrapper to make video sources sendable and usable from Shuffleboard.
+ */
+class SendableCameraWrapper : public Sendable,
+                              public SendableHelper<SendableCameraWrapper> {
+ private:
+  struct private_init {};
+
+ public:
+  /**
+   * Creates a new sendable wrapper. Private constructor to avoid direct
+   * instantiation with multiple wrappers floating around for the same camera.
+   *
+   * @param source the source to wrap
+   */
+  SendableCameraWrapper(CS_Source source, const private_init&);
+
+  /**
+   * Gets a sendable wrapper object for the given video source, creating the
+   * wrapper if one does not already exist for the source.
+   *
+   * @param source the video source to wrap
+   * @return a sendable wrapper object for the video source, usable in
+   * Shuffleboard via ShuffleboardTab::Add() and ShuffleboardLayout::Add()
+   */
+  static SendableCameraWrapper& Wrap(const cs::VideoSource& source);
+  static SendableCameraWrapper& Wrap(CS_Source source);
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  std::string m_uri;
+};
+
+#ifndef DYNAMIC_CAMERA_SERVER
+inline SendableCameraWrapper::SendableCameraWrapper(CS_Source source,
+                                                    const private_init&)
+    : m_uri(detail::kProtocol) {
+  CS_Status status = 0;
+  auto name = cs::GetSourceName(source, &status);
+  detail::AddToSendableRegistry(this, name);
+  m_uri += name;
+}
+
+inline SendableCameraWrapper& SendableCameraWrapper::Wrap(
+    const cs::VideoSource& source) {
+  return Wrap(source.GetHandle());
+}
+
+inline SendableCameraWrapper& SendableCameraWrapper::Wrap(CS_Source source) {
+  auto& wrapper = detail::GetSendableCameraWrapper(source);
+  if (!wrapper)
+    wrapper = std::make_shared<SendableCameraWrapper>(source, private_init{});
+  return *wrapper;
+}
+#endif
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/Shuffleboard.h b/wpilibc/src/main/native/include/frc/shuffleboard/Shuffleboard.h
new file mode 100644
index 0000000..e49d1c3
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/Shuffleboard.h
@@ -0,0 +1,198 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/StringRef.h>
+
+#include "frc/shuffleboard/RecordingController.h"
+#include "frc/shuffleboard/ShuffleboardEventImportance.h"
+#include "frc/shuffleboard/ShuffleboardInstance.h"
+
+namespace frc {
+
+class ShuffleboardTab;
+
+/**
+ * The Shuffleboard class provides a mechanism with which data can be added and
+ * laid out in the Shuffleboard dashboard application from a robot program. Tabs
+ * and layouts can be specified, as well as choosing which widgets to display
+ * with and setting properties of these widgets; for example, programmers can
+ * specify a specific {@code boolean} value to be displayed with a toggle button
+ * instead of the default colored box, or set custom colors for that box.
+ *
+ * For example, displaying a boolean entry with a toggle button:
+ * <pre>{@code
+ * NetworkTableEntry myBoolean = Shuffleboard.getTab("Example Tab")
+ *   .add("My Boolean", false)
+ *   .withWidget("Toggle Button")
+ *   .getEntry();
+ * }</pre>
+ *
+ * Changing the colors of the boolean box:
+ * <pre>{@code
+ * NetworkTableEntry myBoolean = Shuffleboard.getTab("Example Tab")
+ *   .add("My Boolean", false)
+ *   .withWidget("Boolean Box")
+ *   .withProperties(Map.of("colorWhenTrue", "green", "colorWhenFalse",
+ * "maroon")) .getEntry();
+ * }</pre>
+ *
+ * Specifying a parent layout. Note that the layout type must <i>always</i> be
+ * specified, even if the layout has already been generated by a previously
+ * defined entry.
+ * <pre>{@code
+ * NetworkTableEntry myBoolean = Shuffleboard.getTab("Example Tab")
+ *   .getLayout("List", "Example List")
+ *   .add("My Boolean", false)
+ *   .withWidget("Toggle Button")
+ *   .getEntry();
+ * }</pre>
+ * </p>
+ *
+ * Teams are encouraged to set up shuffleboard layouts at the start of the robot
+ * program.
+ */
+class Shuffleboard final {
+ public:
+  /**
+   * The name of the base NetworkTable into which all Shuffleboard data will be
+   * added.
+   */
+  static constexpr const char* kBaseTableName = "/Shuffleboard";
+
+  /**
+   * Updates all the values in Shuffleboard. Iterative and timed robots are
+   * pre-configured to call this method in the main robot loop; teams using
+   * custom robot base classes, or subclass SampleRobot, should make sure to
+   * call this repeatedly to keep data on the dashboard up to date.
+   */
+  static void Update();
+
+  /**
+   * Gets the Shuffleboard tab with the given title, creating it if it does not
+   * already exist.
+   *
+   * @param title the title of the tab
+   * @return the tab with the given title
+   */
+  static ShuffleboardTab& GetTab(wpi::StringRef title);
+
+  /**
+   * Selects the tab in the dashboard with the given index in the range
+   * [0..n-1], where <i>n</i> is the number of tabs in the dashboard at the time
+   * this method is called.
+   *
+   * @param index the index of the tab to select
+   */
+  static void SelectTab(int index);
+
+  /**
+   * Selects the tab in the dashboard with the given title.
+   *
+   * @param title the title of the tab to select
+   */
+  static void SelectTab(wpi::StringRef title);
+
+  /**
+   * Enables user control of widgets containing actuators: speed controllers,
+   * relays, etc. This should only be used when the robot is in test mode.
+   * IterativeRobotBase and SampleRobot are both configured to call this method
+   * when entering test mode; most users should not need to use this method
+   * directly.
+   */
+  static void EnableActuatorWidgets();
+
+  /**
+   * Disables user control of widgets containing actuators. For safety reasons,
+   * actuators should only be controlled while in test mode. IterativeRobotBase
+   * and SampleRobot are both configured to call this method when exiting in
+   * test mode; most users should not need to use this method directly.
+   */
+  static void DisableActuatorWidgets();
+
+  /**
+   * Starts data recording on the dashboard. Has no effect if recording is
+   * already in progress.
+   */
+  static void StartRecording();
+
+  /**
+   * Stops data recording on the dashboard. Has no effect if no recording is in
+   * progress.
+   */
+  static void StopRecording();
+
+  /**
+   * Sets the file name format for new recording files to use. If recording is
+   * in progress when this method is called, it will continue to use the same
+   * file. New recordings will use the format.
+   *
+   * <p>To avoid recording files overwriting each other, make sure to use unique
+   * recording file names. File name formats accept templates for inserting the
+   * date and time when the recording started with the {@code ${date}} and
+   * {@code ${time}} templates, respectively. For example, the default format is
+   * {@code "recording-${time}"} and recording files created with it will have
+   * names like {@code "recording-2018.01.15.sbr"}. Users are
+   * <strong>strongly</strong> recommended to use the {@code ${time}} template
+   * to ensure unique file names.
+   * </p>
+   *
+   * @param format the format for the
+   */
+  static void SetRecordingFileNameFormat(wpi::StringRef format);
+
+  /**
+   * Clears the custom name format for recording files. New recordings will use
+   * the default format.
+   *
+   * @see #setRecordingFileNameFormat(String)
+   */
+  static void ClearRecordingFileNameFormat();
+
+  /**
+   * Notifies Shuffleboard of an event. Events can range from as trivial as a
+   * change in a command state to as critical as a total power loss or component
+   * failure. If Shuffleboard is recording, the event will also be recorded.
+   *
+   * <p>If {@code name} is {@code null} or empty, no event will be sent and an
+   * error will be printed to the driver station.
+   *
+   * @param name        the name of the event
+   * @param description a description of the event
+   * @param importance  the importance of the event
+   */
+  static void AddEventMarker(wpi::StringRef name, wpi::StringRef description,
+                             ShuffleboardEventImportance importance);
+
+  /**
+   * Notifies Shuffleboard of an event. Events can range from as trivial as a
+   * change in a command state to as critical as a total power loss or component
+   * failure. If Shuffleboard is recording, the event will also be recorded.
+   *
+   * <p>If {@code name} is {@code null} or empty, no event will be sent and an
+   * error will be printed to the driver station.
+   *
+   * @param name        the name of the event
+   * @param importance  the importance of the event
+   */
+  static void AddEventMarker(wpi::StringRef name,
+                             ShuffleboardEventImportance importance);
+
+ private:
+  static detail::ShuffleboardInstance& GetInstance();
+  static detail::RecordingController& GetRecordingController();
+
+  // TODO usage reporting
+
+  Shuffleboard() = default;
+};
+
+}  // namespace frc
+
+// Make use of references returned by member functions usable
+#include "frc/shuffleboard/ShuffleboardTab.h"
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.h
new file mode 100644
index 0000000..d6b4bc4
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.h
@@ -0,0 +1,76 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableValue.h>
+#include <wpi/StringMap.h>
+#include <wpi/Twine.h>
+
+#include "frc/shuffleboard/ShuffleboardComponentBase.h"
+
+namespace frc {
+
+class ShuffleboardContainer;
+
+/**
+ * A generic component in Shuffleboard.
+ *
+ * @tparam Derived the self type
+ */
+template <typename Derived>
+class ShuffleboardComponent : public ShuffleboardComponentBase {
+ public:
+  ShuffleboardComponent(ShuffleboardContainer& parent, const wpi::Twine& title,
+                        const wpi::Twine& type = "");
+
+  virtual ~ShuffleboardComponent() = default;
+
+  /**
+   * Sets custom properties for this component. Property names are
+   * case-sensitive and whitespace-insensitive (capitalization and spaces do not
+   * matter).
+   *
+   * @param properties the properties for this component
+   * @return this component
+   */
+  Derived& WithProperties(
+      const wpi::StringMap<std::shared_ptr<nt::Value>>& properties);
+
+  /**
+   * Sets the position of this component in the tab. This has no effect if this
+   * component is inside a layout.
+   *
+   * If the position of a single component is set, it is recommended to set the
+   * positions of <i>all</i> components inside a tab to prevent Shuffleboard
+   * from automatically placing another component there before the one with the
+   * specific position is sent.
+   *
+   * @param columnIndex the column in the tab to place this component
+   * @param rowIndex    the row in the tab to place this component
+   * @return this component
+   */
+  Derived& WithPosition(int columnIndex, int rowIndex);
+
+  /**
+   * Sets the size of this component in the tab. This has no effect if this
+   * component is inside a layout.
+   *
+   * @param width  how many columns wide the component should be
+   * @param height how many rows high the component should be
+   * @return this component
+   */
+  Derived& WithSize(int width, int height);
+};
+
+}  // namespace frc
+
+#include "frc/shuffleboard/ShuffleboardComponent.inc"
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.inc b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.inc
new file mode 100644
index 0000000..f75fb0d
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.inc
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+namespace frc {
+
+template <typename Derived>
+ShuffleboardComponent<Derived>::ShuffleboardComponent(
+    ShuffleboardContainer& parent, const wpi::Twine& title,
+    const wpi::Twine& type)
+    : ShuffleboardValue(title),
+      ShuffleboardComponentBase(parent, title, type) {}
+
+template <typename Derived>
+Derived& ShuffleboardComponent<Derived>::WithProperties(
+    const wpi::StringMap<std::shared_ptr<nt::Value>>& properties) {
+  m_properties = properties;
+  m_metadataDirty = true;
+  return *static_cast<Derived*>(this);
+}
+
+template <typename Derived>
+Derived& ShuffleboardComponent<Derived>::WithPosition(int columnIndex,
+                                                      int rowIndex) {
+  m_column = columnIndex;
+  m_row = rowIndex;
+  m_metadataDirty = true;
+  return *static_cast<Derived*>(this);
+}
+
+template <typename Derived>
+Derived& ShuffleboardComponent<Derived>::WithSize(int width, int height) {
+  m_width = width;
+  m_height = height;
+  m_metadataDirty = true;
+  return *static_cast<Derived*>(this);
+}
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponentBase.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponentBase.h
new file mode 100644
index 0000000..c63e517
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponentBase.h
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableValue.h>
+#include <wpi/StringMap.h>
+#include <wpi/Twine.h>
+
+#include "frc/shuffleboard/ShuffleboardValue.h"
+
+namespace frc {
+
+class ShuffleboardContainer;
+
+/**
+ * A shim class to allow storing ShuffleboardComponents in arrays.
+ */
+class ShuffleboardComponentBase : public virtual ShuffleboardValue {
+ public:
+  ShuffleboardComponentBase(ShuffleboardContainer& parent,
+                            const wpi::Twine& title,
+                            const wpi::Twine& type = "");
+
+  virtual ~ShuffleboardComponentBase() = default;
+
+  void SetType(const wpi::Twine& type);
+
+  void BuildMetadata(std::shared_ptr<nt::NetworkTable> metaTable);
+
+  ShuffleboardContainer& GetParent();
+
+  const std::string& GetType() const;
+
+ protected:
+  wpi::StringMap<std::shared_ptr<nt::Value>> m_properties;
+  bool m_metadataDirty = true;
+  int m_column = -1;
+  int m_row = -1;
+  int m_width = -1;
+  int m_height = -1;
+
+ private:
+  ShuffleboardContainer& m_parent;
+  std::string m_type;
+
+  /**
+   * Gets the custom properties for this component. May be null.
+   */
+  const wpi::StringMap<std::shared_ptr<nt::Value>>& GetProperties() const;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h
new file mode 100644
index 0000000..7b8b49d
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h
@@ -0,0 +1,517 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableValue.h>
+#include <wpi/ArrayRef.h>
+#include <wpi/SmallSet.h>
+#include <wpi/StringMap.h>
+#include <wpi/Twine.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/WPIErrors.h"
+#include "frc/shuffleboard/BuiltInLayouts.h"
+#include "frc/shuffleboard/LayoutType.h"
+#include "frc/shuffleboard/ShuffleboardComponentBase.h"
+#include "frc/shuffleboard/ShuffleboardValue.h"
+#include "frc/shuffleboard/SuppliedValueWidget.h"
+
+namespace cs {
+class VideoSource;
+}  // namespace cs
+
+namespace frc {
+
+class ComplexWidget;
+class Sendable;
+class ShuffleboardLayout;
+class SimpleWidget;
+
+/**
+ * Common interface for objects that can contain shuffleboard components.
+ */
+class ShuffleboardContainer : public virtual ShuffleboardValue,
+                              public ErrorBase {
+ public:
+  explicit ShuffleboardContainer(const wpi::Twine& title);
+
+  ShuffleboardContainer(ShuffleboardContainer&& rhs) = default;
+
+  virtual ~ShuffleboardContainer() = default;
+
+  /**
+   * Gets the components that are direct children of this container.
+   */
+  const std::vector<std::unique_ptr<ShuffleboardComponentBase>>& GetComponents()
+      const;
+
+  /**
+   * Gets the layout with the given type and title, creating it if it does not
+   * already exist at the time this method is called.
+   *
+   * @param title      the title of the layout
+   * @param layoutType the type of the layout, eg "List" or "Grid"
+   * @return the layout
+   */
+  ShuffleboardLayout& GetLayout(const wpi::Twine& title, BuiltInLayouts type);
+
+  /**
+   * Gets the layout with the given type and title, creating it if it does not
+   * already exist at the time this method is called.
+   *
+   * @param title      the title of the layout
+   * @param layoutType the type of the layout, eg "List" or "Grid"
+   * @return the layout
+   */
+  ShuffleboardLayout& GetLayout(const wpi::Twine& title,
+                                const LayoutType& type);
+
+  /**
+   * Gets the layout with the given type and title, creating it if it does not
+   * already exist at the time this method is called. Note: this method should
+   * only be used to use a layout type that is not already built into
+   * Shuffleboard. To use a layout built into Shuffleboard, use
+   * {@link #GetLayout(String, LayoutType)} and the layouts in {@link
+   * BuiltInLayouts}.
+   *
+   * @param title the title of the layout
+   * @param type  the type of the layout, eg "List Layout" or "Grid Layout"
+   * @return the layout
+   * @see #GetLayout(String, LayoutType)
+   */
+  ShuffleboardLayout& GetLayout(const wpi::Twine& title,
+                                const wpi::Twine& type);
+
+  /**
+   * Gets the already-defined layout in this container with the given title.
+   *
+   * <pre>{@code
+   * Shuffleboard::GetTab("Example Tab")->getLayout("My Layout",
+   * &BuiltInLayouts.kList);
+   *
+   * // Later...
+   * Shuffleboard::GetTab("Example Tab")->GetLayout("My Layout");
+   * }</pre>
+   *
+   * @param title the title of the layout to get
+   * @return the layout with the given title
+   * @throws if no layout has yet been defined with the given title
+   */
+  ShuffleboardLayout& GetLayout(const wpi::Twine& title);
+
+  /**
+   * Adds a widget to this container to display the given sendable.
+   *
+   * @param title    the title of the widget
+   * @param sendable the sendable to display
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   * container with the given title
+   */
+  ComplexWidget& Add(const wpi::Twine& title, Sendable& sendable);
+
+  /**
+   * Adds a widget to this container to display the given video stream.
+   *
+   * @param title    the title of the widget
+   * @param video    the video stream to display
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   * container with the given title
+   */
+  ComplexWidget& Add(const wpi::Twine& title, const cs::VideoSource& video);
+
+  /**
+   * Adds a widget to this container to display the given sendable.
+   *
+   * @param sendable the sendable to display
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   * container with the given title, or if the sendable's name has not been
+   * specified
+   */
+  ComplexWidget& Add(Sendable& sendable);
+
+  /**
+   * Adds a widget to this container to display the given video stream.
+   *
+   * @param video the video to display
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   * container with the same title as the video source
+   */
+  ComplexWidget& Add(const cs::VideoSource& video);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title,
+                    std::shared_ptr<nt::Value> defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title, bool defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title, double defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title, int defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title, const wpi::Twine& defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title, const char* defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title, wpi::ArrayRef<bool> defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title,
+                    wpi::ArrayRef<double> defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title,
+                    wpi::ArrayRef<std::string> defaultValue);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided
+   * by the value supplier. Changes made on the dashboard will not propagate to
+   * the widget object, and will be overridden by values from the value
+   * supplier.
+   *
+   * @param title the title of the widget
+   * @param valueSupplier the supplier for values
+   * @return a widget to display data
+   */
+  SuppliedValueWidget<std::string>& AddString(
+      const wpi::Twine& title, std::function<std::string()> supplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided
+   * by the value supplier. Changes made on the dashboard will not propagate to
+   * the widget object, and will be overridden by values from the value
+   * supplier.
+   *
+   * @param title the title of the widget
+   * @param valueSupplier the supplier for values
+   * @return a widget to display data
+   */
+  SuppliedValueWidget<double>& AddNumber(const wpi::Twine& title,
+                                         std::function<double()> supplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided
+   * by the value supplier. Changes made on the dashboard will not propagate to
+   * the widget object, and will be overridden by values from the value
+   * supplier.
+   *
+   * @param title the title of the widget
+   * @param valueSupplier the supplier for values
+   * @return a widget to display data
+   */
+  SuppliedValueWidget<bool>& AddBoolean(const wpi::Twine& title,
+                                        std::function<bool()> supplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided
+   * by the value supplier. Changes made on the dashboard will not propagate to
+   * the widget object, and will be overridden by values from the value
+   * supplier.
+   *
+   * @param title the title of the widget
+   * @param valueSupplier the supplier for values
+   * @return a widget to display data
+   */
+  SuppliedValueWidget<std::vector<std::string>>& AddStringArray(
+      const wpi::Twine& title,
+      std::function<std::vector<std::string>()> supplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided
+   * by the value supplier. Changes made on the dashboard will not propagate to
+   * the widget object, and will be overridden by values from the value
+   * supplier.
+   *
+   * @param title the title of the widget
+   * @param valueSupplier the supplier for values
+   * @return a widget to display data
+   */
+  SuppliedValueWidget<std::vector<double>>& AddNumberArray(
+      const wpi::Twine& title, std::function<std::vector<double>()> supplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided
+   * by the value supplier. Changes made on the dashboard will not propagate to
+   * the widget object, and will be overridden by values from the value
+   * supplier.
+   *
+   * @param title the title of the widget
+   * @param valueSupplier the supplier for values
+   * @return a widget to display data
+   */
+  SuppliedValueWidget<std::vector<int>>& AddBooleanArray(
+      const wpi::Twine& title, std::function<std::vector<int>()> supplier);
+
+  /**
+   * Adds a widget to this container. The widget will display the data provided
+   * by the value supplier. Changes made on the dashboard will not propagate to
+   * the widget object, and will be overridden by values from the value
+   * supplier.
+   *
+   * @param title the title of the widget
+   * @param valueSupplier the supplier for values
+   * @return a widget to display data
+   */
+  SuppliedValueWidget<wpi::StringRef>& AddRaw(
+      const wpi::Twine& title, std::function<wpi::StringRef()> supplier);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title,
+                              std::shared_ptr<nt::Value> defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title, bool defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title, double defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title, int defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title,
+                              const wpi::Twine& defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title,
+                              wpi::ArrayRef<bool> defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title,
+                              wpi::ArrayRef<double> defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title,
+                              wpi::ArrayRef<std::string> defaultValue);
+
+  void EnableIfActuator() override;
+
+  void DisableIfActuator() override;
+
+ protected:
+  bool m_isLayout = false;
+
+ private:
+  wpi::SmallSet<std::string, 32> m_usedTitles;
+  std::vector<std::unique_ptr<ShuffleboardComponentBase>> m_components;
+  wpi::StringMap<ShuffleboardLayout*> m_layouts;
+
+  /**
+   * Adds title to internal set if it hasn't already.
+   *
+   * @return True if title isn't in use; false otherwise.
+   */
+  void CheckTitle(const wpi::Twine& title);
+
+  friend class SimpleWidget;
+};
+
+}  // namespace frc
+
+// Make use of references returned by member functions usable
+#include "frc/shuffleboard/ComplexWidget.h"
+#include "frc/shuffleboard/ShuffleboardLayout.h"
+#include "frc/shuffleboard/SimpleWidget.h"
+
+#ifndef DYNAMIC_CAMERA_SERVER
+#include "frc/shuffleboard/SendableCameraWrapper.h"
+
+inline frc::ComplexWidget& frc::ShuffleboardContainer::Add(
+    const cs::VideoSource& video) {
+  return Add(frc::SendableCameraWrapper::Wrap(video));
+}
+
+inline frc::ComplexWidget& frc::ShuffleboardContainer::Add(
+    const wpi::Twine& title, const cs::VideoSource& video) {
+  return Add(title, frc::SendableCameraWrapper::Wrap(video));
+}
+#endif
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardEventImportance.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardEventImportance.h
new file mode 100644
index 0000000..ccbc802
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardEventImportance.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+// Maintainer note: this enum is mirrored in WPILibJ and in Shuffleboard
+// Modifying the enum or enum strings requires a corresponding change to the
+// Java enum and the enum in Shuffleboard
+
+enum ShuffleboardEventImportance { kTrivial, kLow, kNormal, kHigh, kCritical };
+
+inline wpi::StringRef ShuffleboardEventImportanceName(
+    ShuffleboardEventImportance importance) {
+  switch (importance) {
+    case kTrivial:
+      return "TRIVIAL";
+    case kLow:
+      return "LOW";
+    case kNormal:
+      return "NORMAL";
+    case kHigh:
+      return "HIGH";
+    case kCritical:
+      return "CRITICAL";
+    default:
+      return "NORMAL";
+  }
+}
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardInstance.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardInstance.h
new file mode 100644
index 0000000..b202160
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardInstance.h
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include "frc/shuffleboard/ShuffleboardRoot.h"
+#include "frc/shuffleboard/ShuffleboardTab.h"
+
+namespace frc {
+namespace detail {
+
+class ShuffleboardInstance final : public ShuffleboardRoot {
+ public:
+  explicit ShuffleboardInstance(nt::NetworkTableInstance ntInstance);
+  virtual ~ShuffleboardInstance();
+
+  frc::ShuffleboardTab& GetTab(wpi::StringRef title) override;
+
+  void Update() override;
+
+  void EnableActuatorWidgets() override;
+
+  void DisableActuatorWidgets() override;
+
+  void SelectTab(int index) override;
+
+  void SelectTab(wpi::StringRef) override;
+
+ private:
+  struct Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+}  // namespace detail
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardLayout.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardLayout.h
new file mode 100644
index 0000000..effa3da
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardLayout.h
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <networktables/NetworkTable.h>
+#include <wpi/Twine.h>
+
+#include "frc/shuffleboard/ShuffleboardComponent.h"
+#include "frc/shuffleboard/ShuffleboardContainer.h"
+
+#ifdef _WIN32
+#pragma warning(push)
+#pragma warning(disable : 4250)
+#endif
+
+namespace frc {
+
+/**
+ * A layout in a Shuffleboard tab. Layouts can contain widgets and other
+ * layouts.
+ */
+class ShuffleboardLayout : public ShuffleboardComponent<ShuffleboardLayout>,
+                           public ShuffleboardContainer {
+ public:
+  ShuffleboardLayout(ShuffleboardContainer& parent, const wpi::Twine& name,
+                     const wpi::Twine& type);
+
+  void BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                 std::shared_ptr<nt::NetworkTable> metaTable) override;
+};
+
+}  // namespace frc
+
+#ifdef _WIN32
+#pragma warning(pop)
+#endif
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardRoot.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardRoot.h
new file mode 100644
index 0000000..0c50545
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardRoot.h
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/StringRef.h>
+
+namespace frc {
+
+class ShuffleboardTab;
+
+/**
+ * The root of the data placed in Shuffleboard. It contains the tabs, but no
+ * data is placed directly in the root.
+ *
+ * This class is package-private to minimize API surface area.
+ */
+class ShuffleboardRoot {
+ public:
+  /**
+   * Gets the tab with the given title, creating it if it does not already
+   * exist.
+   *
+   * @param title the title of the tab
+   * @return the tab with the given title
+   */
+  virtual ShuffleboardTab& GetTab(wpi::StringRef title) = 0;
+
+  /**
+   * Updates all tabs.
+   */
+  virtual void Update() = 0;
+
+  /**
+   * Enables all widgets in Shuffleboard that offer user control over actuators.
+   */
+  virtual void EnableActuatorWidgets() = 0;
+
+  /**
+   * Disables all widgets in Shuffleboard that offer user control over
+   * actuators.
+   */
+  virtual void DisableActuatorWidgets() = 0;
+
+  /**
+   * Selects the tab in the dashboard with the given index in the range
+   * [0..n-1], where <i>n</i> is the number of tabs in the dashboard at the time
+   * this method is called.
+   *
+   * @param index the index of the tab to select
+   */
+  virtual void SelectTab(int index) = 0;
+
+  /**
+   * Selects the tab in the dashboard with the given title.
+   *
+   * @param title the title of the tab to select
+   */
+  virtual void SelectTab(wpi::StringRef title) = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardTab.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardTab.h
new file mode 100644
index 0000000..75896ae
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardTab.h
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <networktables/NetworkTable.h>
+#include <wpi/StringRef.h>
+
+#include "frc/shuffleboard/ShuffleboardContainer.h"
+
+namespace frc {
+
+class ShuffleboardRoot;
+
+/**
+ * Represents a tab in the Shuffleboard dashboard. Widgets can be added to the
+ * tab with {@link #add(Sendable)}, {@link #add(String, Object)}, and
+ * {@link #add(String, Sendable)}. Widgets can also be added to layouts with
+ * {@link #getLayout(String, String)}; layouts can be nested arbitrarily deep
+ * (note that too many levels may make deeper components unusable).
+ */
+class ShuffleboardTab final : public ShuffleboardContainer {
+ public:
+  ShuffleboardTab(ShuffleboardRoot& root, wpi::StringRef title);
+
+  ShuffleboardRoot& GetRoot();
+
+  void BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                 std::shared_ptr<nt::NetworkTable> metaTable) override;
+
+ private:
+  ShuffleboardRoot& m_root;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardValue.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardValue.h
new file mode 100644
index 0000000..4a88cc1
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardValue.h
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <networktables/NetworkTable.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringRef.h>
+
+namespace frc {
+
+class ShuffleboardValue {
+ public:
+  explicit ShuffleboardValue(const wpi::Twine& title) {
+    wpi::SmallVector<char, 16> storage;
+    m_title = title.toStringRef(storage);
+  }
+
+  virtual ~ShuffleboardValue() = default;
+
+  /**
+   * Gets the title of this Shuffleboard value.
+   */
+  wpi::StringRef GetTitle() const { return m_title; }
+
+  /**
+   * Builds the entries for this value.
+   *
+   * @param parentTable The table containing all the data for the parent. Values
+   *                    that require a complex entry or table structure should
+   *                    call {@code parentTable.getSubtable(getTitle())} to get
+   *                    the table to put data into. Values that only use a
+   *                    single entry should call
+   *                    {@code parentTable.getEntry(getTitle())} to get that
+   *                    entry.
+   * @param metaTable   The table containing all the metadata for this value and
+   *                    its sub-values
+   */
+  virtual void BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                         std::shared_ptr<nt::NetworkTable> metaTable) = 0;
+
+  /**
+   * Enables user control of this widget in the Shuffleboard application.
+   *
+   * This method is package-private to prevent users from enabling control
+   * themselves. Has no effect if the sendable is not marked as an actuator with
+   * {@link SendableBuilder#setActuator}.
+   */
+  virtual void EnableIfActuator() {}
+
+  /**
+   * Disables user control of this widget in the Shuffleboard application.
+   *
+   * This method is package-private to prevent users from enabling control
+   * themselves. Has no effect if the sendable is not marked as an actuator with
+   * {@link SendableBuilder#setActuator}.
+   */
+  virtual void DisableIfActuator() {}
+
+ private:
+  std::string m_title;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardWidget.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardWidget.h
new file mode 100644
index 0000000..ea92b93
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardWidget.h
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/Twine.h>
+
+#include "frc/shuffleboard/BuiltInWidgets.h"
+#include "frc/shuffleboard/ShuffleboardComponent.h"
+#include "frc/shuffleboard/WidgetType.h"
+
+namespace frc {
+
+class ShuffleboardContainer;
+
+namespace detail {
+const char* GetStringForWidgetType(BuiltInWidgets type);
+}  // namespace detail
+
+/**
+ * Abstract superclass for widgets.
+ *
+ * <p>This class is package-private to minimize API surface area.
+ *
+ * @tparam Derived the self type
+ */
+template <typename Derived>
+class ShuffleboardWidget : public ShuffleboardComponent<Derived> {
+ public:
+  ShuffleboardWidget(ShuffleboardContainer& parent, const wpi::Twine& title)
+      : ShuffleboardValue(title),
+        ShuffleboardComponent<Derived>(parent, title) {}
+
+  /**
+   * Sets the type of widget used to display the data. If not set, the default
+   * widget type will be used.
+   *
+   * @param widgetType the type of the widget used to display the data
+   * @return this widget object
+   * @see BuiltInWidgets
+   */
+  Derived& WithWidget(BuiltInWidgets widgetType) {
+    return WithWidget(detail::GetStringForWidgetType(widgetType));
+  }
+
+  /**
+   * Sets the type of widget used to display the data. If not set, the default
+   * widget type will be used.
+   *
+   * @param widgetType the type of the widget used to display the data
+   * @return this widget object
+   */
+  Derived& WithWidget(const WidgetType& widgetType) {
+    return WithWidget(widgetType.GetWidgetName());
+  }
+
+  /**
+   * Sets the type of widget used to display the data. If not set, the default
+   * widget type will be used. This method should only be used to use a widget
+   * that does not come built into Shuffleboard (i.e. one that comes with a
+   * custom or thrid-party plugin). To use a widget that is built into
+   * Shuffleboard, use {@link #withWidget(WidgetType)} and {@link
+   * BuiltInWidgets}.
+   *
+   * @param widgetType the type of the widget used to display the data
+   * @return this widget object
+   */
+  Derived& WithWidget(const wpi::Twine& widgetType) {
+    this->SetType(widgetType);
+    return *static_cast<Derived*>(this);
+  }
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/SimpleWidget.h b/wpilibc/src/main/native/include/frc/shuffleboard/SimpleWidget.h
new file mode 100644
index 0000000..973f8cb
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/SimpleWidget.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableEntry.h>
+#include <wpi/Twine.h>
+
+#include "frc/shuffleboard/ShuffleboardWidget.h"
+
+namespace frc {
+
+class ShuffleboardContainer;
+
+/**
+ * A Shuffleboard widget that handles a single data point such as a number or
+ * string.
+ */
+class SimpleWidget final : public ShuffleboardWidget<SimpleWidget> {
+ public:
+  SimpleWidget(ShuffleboardContainer& parent, const wpi::Twine& title);
+
+  /**
+   * Gets the NetworkTable entry that contains the data for this widget.
+   */
+  nt::NetworkTableEntry GetEntry();
+
+  void BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                 std::shared_ptr<nt::NetworkTable> metaTable) override;
+
+ private:
+  nt::NetworkTableEntry m_entry;
+
+  void ForceGenerate();
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/SuppliedValueWidget.h b/wpilibc/src/main/native/include/frc/shuffleboard/SuppliedValueWidget.h
new file mode 100644
index 0000000..c806db4
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/SuppliedValueWidget.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+#include <memory>
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableEntry.h>
+#include <wpi/Twine.h>
+
+#include "frc/shuffleboard/ShuffleboardComponent.h"
+#include "frc/shuffleboard/ShuffleboardComponent.inc"
+#include "frc/shuffleboard/ShuffleboardComponentBase.h"
+#include "frc/shuffleboard/ShuffleboardContainer.h"
+#include "frc/shuffleboard/ShuffleboardWidget.h"
+
+namespace frc {
+template <typename T>
+class SuppliedValueWidget : public ShuffleboardWidget<SuppliedValueWidget<T> > {
+ public:
+  SuppliedValueWidget(ShuffleboardContainer& parent, const wpi::Twine& title,
+                      std::function<T()> supplier,
+                      std::function<void(nt::NetworkTableEntry, T)> setter)
+      : ShuffleboardValue(title),
+        ShuffleboardWidget<SuppliedValueWidget<T> >(parent, title),
+        m_supplier(supplier),
+        m_setter(setter) {}
+
+  void BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                 std::shared_ptr<nt::NetworkTable> metaTable) override {
+    this->BuildMetadata(metaTable);
+    metaTable->GetEntry("Controllable").SetBoolean(false);
+
+    auto entry = parentTable->GetEntry(this->GetTitle());
+    m_setter(entry, m_supplier());
+  }
+
+ private:
+  std::function<T()> m_supplier;
+  std::function<void(nt::NetworkTableEntry, T)> m_setter;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/WidgetType.h b/wpilibc/src/main/native/include/frc/shuffleboard/WidgetType.h
new file mode 100644
index 0000000..ff92fe7
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/WidgetType.h
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/StringRef.h>
+
+namespace frc {
+
+/**
+ * Represents the type of a widget in Shuffleboard. Using this is preferred over
+ * specifying raw strings, to avoid typos and having to know or look up the
+ * exact string name for a desired widget.
+ *
+ * @see BuiltInWidgets the built-in widget types
+ */
+class WidgetType {
+ public:
+  explicit constexpr WidgetType(const char* widgetName)
+      : m_widgetName(widgetName) {}
+  ~WidgetType() = default;
+
+  /**
+   * Gets the string type of the widget as defined by that widget in
+   * Shuffleboard.
+   */
+  wpi::StringRef GetWidgetName() const;
+
+ private:
+  const char* m_widgetName;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/ListenerExecutor.h b/wpilibc/src/main/native/include/frc/smartdashboard/ListenerExecutor.h
new file mode 100644
index 0000000..9500278
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/smartdashboard/ListenerExecutor.h
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+#include <vector>
+
+#include <wpi/mutex.h>
+
+namespace frc::detail {
+/**
+ * An executor for running listener tasks posted by Sendable listeners
+ * synchronously from the main application thread.
+ *
+ * @see Sendable
+ */
+class ListenerExecutor {
+ public:
+  /**
+   * Posts a task to the executor to be run synchronously from the main thread.
+   *
+   * @param task The task to run synchronously from the main thread.
+   */
+  void Execute(std::function<void()> task);
+
+  /**
+   * Runs all posted tasks.  Called periodically from main thread.
+   */
+  void RunListenerTasks();
+
+ private:
+  std::vector<std::function<void()>> m_tasks;
+  std::vector<std::function<void()>> m_runningTasks;
+  wpi::mutex m_lock;
+};
+}  // namespace frc::detail
diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/Sendable.h b/wpilibc/src/main/native/include/frc/smartdashboard/Sendable.h
new file mode 100644
index 0000000..5000855
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/smartdashboard/Sendable.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and 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 SendableBuilder;
+
+/**
+ * Interface for Sendable objects.
+ */
+class Sendable {
+ public:
+  virtual ~Sendable() = default;
+
+  /**
+   * Initializes this Sendable object.
+   *
+   * @param builder sendable builder
+   */
+  virtual void InitSendable(SendableBuilder& builder) = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBase.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBase.h
new file mode 100644
index 0000000..a0ea0f9
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBase.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/deprecated.h>
+
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SendableBase : public Sendable, public SendableHelper<SendableBase> {
+ public:
+  /**
+   * Creates an instance of the sensor base.
+   *
+   * @param addLiveWindow if true, add this Sendable to LiveWindow
+   */
+  WPI_DEPRECATED("use Sendable and SendableHelper")
+  explicit SendableBase(bool addLiveWindow = true);
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilder.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilder.h
new file mode 100644
index 0000000..3f5f892
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilder.h
@@ -0,0 +1,222 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableValue.h>
+#include <wpi/ArrayRef.h>
+#include <wpi/SmallVector.h>
+#include <wpi/Twine.h>
+
+namespace frc {
+
+class SendableBuilder {
+ public:
+  virtual ~SendableBuilder() = default;
+
+  /**
+   * Set the string representation of the named data type that will be used
+   * by the smart dashboard for this sendable.
+   *
+   * @param type    data type
+   */
+  virtual void SetSmartDashboardType(const wpi::Twine& type) = 0;
+
+  /**
+   * Set a flag indicating if this sendable should be treated as an actuator.
+   * By default this flag is false.
+   *
+   * @param value   true if actuator, false if not
+   */
+  virtual void SetActuator(bool value) = 0;
+
+  /**
+   * Set the function that should be called to set the Sendable into a safe
+   * state.  This is called when entering and exiting Live Window mode.
+   *
+   * @param func    function
+   */
+  virtual void SetSafeState(std::function<void()> func) = 0;
+
+  /**
+   * Set the function that should be called to update the network table
+   * for things other than properties.  Note this function is not passed
+   * the network table object; instead it should use the entry handles
+   * returned by GetEntry().
+   *
+   * @param func    function
+   */
+  virtual void SetUpdateTable(std::function<void()> func) = 0;
+
+  /**
+   * Add a property without getters or setters.  This can be used to get
+   * entry handles for the function called by SetUpdateTable().
+   *
+   * @param key   property name
+   * @return Network table entry
+   */
+  virtual nt::NetworkTableEntry GetEntry(const wpi::Twine& key) = 0;
+
+  /**
+   * Add a boolean property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddBooleanProperty(const wpi::Twine& key,
+                                  std::function<bool()> getter,
+                                  std::function<void(bool)> setter) = 0;
+
+  /**
+   * Add a double property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddDoubleProperty(const wpi::Twine& key,
+                                 std::function<double()> getter,
+                                 std::function<void(double)> setter) = 0;
+
+  /**
+   * Add a string property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddStringProperty(
+      const wpi::Twine& key, std::function<std::string()> getter,
+      std::function<void(wpi::StringRef)> setter) = 0;
+
+  /**
+   * Add a boolean array property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddBooleanArrayProperty(
+      const wpi::Twine& key, std::function<std::vector<int>()> getter,
+      std::function<void(wpi::ArrayRef<int>)> setter) = 0;
+
+  /**
+   * Add a double array property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddDoubleArrayProperty(
+      const wpi::Twine& key, std::function<std::vector<double>()> getter,
+      std::function<void(wpi::ArrayRef<double>)> setter) = 0;
+
+  /**
+   * Add a string array property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddStringArrayProperty(
+      const wpi::Twine& key, std::function<std::vector<std::string>()> getter,
+      std::function<void(wpi::ArrayRef<std::string>)> setter) = 0;
+
+  /**
+   * Add a raw property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddRawProperty(const wpi::Twine& key,
+                              std::function<std::string()> getter,
+                              std::function<void(wpi::StringRef)> setter) = 0;
+
+  /**
+   * Add a NetworkTableValue property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddValueProperty(
+      const wpi::Twine& key, std::function<std::shared_ptr<nt::Value>()> getter,
+      std::function<void(std::shared_ptr<nt::Value>)> setter) = 0;
+
+  /**
+   * Add a string property (SmallString form).
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddSmallStringProperty(
+      const wpi::Twine& key,
+      std::function<wpi::StringRef(wpi::SmallVectorImpl<char>& buf)> getter,
+      std::function<void(wpi::StringRef)> setter) = 0;
+
+  /**
+   * Add a boolean array property (SmallVector form).
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddSmallBooleanArrayProperty(
+      const wpi::Twine& key,
+      std::function<wpi::ArrayRef<int>(wpi::SmallVectorImpl<int>& buf)> getter,
+      std::function<void(wpi::ArrayRef<int>)> setter) = 0;
+
+  /**
+   * Add a double array property (SmallVector form).
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddSmallDoubleArrayProperty(
+      const wpi::Twine& key,
+      std::function<wpi::ArrayRef<double>(wpi::SmallVectorImpl<double>& buf)>
+          getter,
+      std::function<void(wpi::ArrayRef<double>)> setter) = 0;
+
+  /**
+   * Add a string array property (SmallVector form).
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddSmallStringArrayProperty(
+      const wpi::Twine& key,
+      std::function<
+          wpi::ArrayRef<std::string>(wpi::SmallVectorImpl<std::string>& buf)>
+          getter,
+      std::function<void(wpi::ArrayRef<std::string>)> setter) = 0;
+
+  /**
+   * Add a raw property (SmallVector form).
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddSmallRawProperty(
+      const wpi::Twine& key,
+      std::function<wpi::StringRef(wpi::SmallVectorImpl<char>& buf)> getter,
+      std::function<void(wpi::StringRef)> setter) = 0;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h
new file mode 100644
index 0000000..eb69dcd
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h
@@ -0,0 +1,211 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+#include <memory>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableValue.h>
+#include <wpi/ArrayRef.h>
+#include <wpi/SmallVector.h>
+#include <wpi/Twine.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+
+namespace frc {
+
+class SendableBuilderImpl : public SendableBuilder {
+ public:
+  SendableBuilderImpl() = default;
+  ~SendableBuilderImpl() override = default;
+
+  SendableBuilderImpl(SendableBuilderImpl&&) = default;
+  SendableBuilderImpl& operator=(SendableBuilderImpl&&) = default;
+
+  /**
+   * Set the network table.  Must be called prior to any Add* functions being
+   * called.
+   * @param table Network table
+   */
+  void SetTable(std::shared_ptr<nt::NetworkTable> table);
+
+  /**
+   * Get the network table.
+   * @return The network table
+   */
+  std::shared_ptr<nt::NetworkTable> GetTable();
+
+  /**
+   * Return whether this sendable has an associated table.
+   * @return True if it has a table, false if not.
+   */
+  bool HasTable() const;
+
+  /**
+   * Return whether this sendable should be treated as an actuator.
+   * @return True if actuator, false if not.
+   */
+  bool IsActuator() const;
+
+  /**
+   * Update the network table values by calling the getters for all properties.
+   */
+  void UpdateTable();
+
+  /**
+   * Hook setters for all properties.
+   */
+  void StartListeners();
+
+  /**
+   * Unhook setters for all properties.
+   */
+  void StopListeners();
+
+  /**
+   * Start LiveWindow mode by hooking the setters for all properties.  Also
+   * calls the SafeState function if one was provided.
+   */
+  void StartLiveWindowMode();
+
+  /**
+   * Stop LiveWindow mode by unhooking the setters for all properties.  Also
+   * calls the SafeState function if one was provided.
+   */
+  void StopLiveWindowMode();
+
+  /**
+   * Clear properties.
+   */
+  void ClearProperties();
+
+  void SetSmartDashboardType(const wpi::Twine& type) override;
+  void SetActuator(bool value) override;
+  void SetSafeState(std::function<void()> func) override;
+  void SetUpdateTable(std::function<void()> func) override;
+  nt::NetworkTableEntry GetEntry(const wpi::Twine& key) override;
+
+  void AddBooleanProperty(const wpi::Twine& key, std::function<bool()> getter,
+                          std::function<void(bool)> setter) override;
+
+  void AddDoubleProperty(const wpi::Twine& key, std::function<double()> getter,
+                         std::function<void(double)> setter) override;
+
+  void AddStringProperty(const wpi::Twine& key,
+                         std::function<std::string()> getter,
+                         std::function<void(wpi::StringRef)> setter) override;
+
+  void AddBooleanArrayProperty(
+      const wpi::Twine& key, std::function<std::vector<int>()> getter,
+      std::function<void(wpi::ArrayRef<int>)> setter) override;
+
+  void AddDoubleArrayProperty(
+      const wpi::Twine& key, std::function<std::vector<double>()> getter,
+      std::function<void(wpi::ArrayRef<double>)> setter) override;
+
+  void AddStringArrayProperty(
+      const wpi::Twine& key, std::function<std::vector<std::string>()> getter,
+      std::function<void(wpi::ArrayRef<std::string>)> setter) override;
+
+  void AddRawProperty(const wpi::Twine& key,
+                      std::function<std::string()> getter,
+                      std::function<void(wpi::StringRef)> setter) override;
+
+  void AddValueProperty(
+      const wpi::Twine& key, std::function<std::shared_ptr<nt::Value>()> getter,
+      std::function<void(std::shared_ptr<nt::Value>)> setter) override;
+
+  void AddSmallStringProperty(
+      const wpi::Twine& key,
+      std::function<wpi::StringRef(wpi::SmallVectorImpl<char>& buf)> getter,
+      std::function<void(wpi::StringRef)> setter) override;
+
+  void AddSmallBooleanArrayProperty(
+      const wpi::Twine& key,
+      std::function<wpi::ArrayRef<int>(wpi::SmallVectorImpl<int>& buf)> getter,
+      std::function<void(wpi::ArrayRef<int>)> setter) override;
+
+  void AddSmallDoubleArrayProperty(
+      const wpi::Twine& key,
+      std::function<wpi::ArrayRef<double>(wpi::SmallVectorImpl<double>& buf)>
+          getter,
+      std::function<void(wpi::ArrayRef<double>)> setter) override;
+
+  void AddSmallStringArrayProperty(
+      const wpi::Twine& key,
+      std::function<
+          wpi::ArrayRef<std::string>(wpi::SmallVectorImpl<std::string>& buf)>
+          getter,
+      std::function<void(wpi::ArrayRef<std::string>)> setter) override;
+
+  void AddSmallRawProperty(
+      const wpi::Twine& key,
+      std::function<wpi::StringRef(wpi::SmallVectorImpl<char>& buf)> getter,
+      std::function<void(wpi::StringRef)> setter) override;
+
+ private:
+  struct Property {
+    Property(nt::NetworkTable& table, const wpi::Twine& key)
+        : entry(table.GetEntry(key)) {}
+
+    Property(const Property&) = delete;
+    Property& operator=(const Property&) = delete;
+
+    Property(Property&& other) noexcept
+        : entry(other.entry),
+          listener(other.listener),
+          update(std::move(other.update)),
+          createListener(std::move(other.createListener)) {
+      other.entry = nt::NetworkTableEntry();
+      other.listener = 0;
+    }
+
+    Property& operator=(Property&& other) noexcept {
+      entry = other.entry;
+      listener = other.listener;
+      other.entry = nt::NetworkTableEntry();
+      other.listener = 0;
+      update = std::move(other.update);
+      createListener = std::move(other.createListener);
+      return *this;
+    }
+
+    ~Property() { StopListener(); }
+
+    void StartListener() {
+      if (entry && listener == 0 && createListener)
+        listener = createListener(entry);
+    }
+
+    void StopListener() {
+      if (entry && listener != 0) {
+        entry.RemoveListener(listener);
+        listener = 0;
+      }
+    }
+
+    nt::NetworkTableEntry entry;
+    NT_EntryListener listener = 0;
+    std::function<void(nt::NetworkTableEntry entry, uint64_t time)> update;
+    std::function<NT_EntryListener(nt::NetworkTableEntry entry)> createListener;
+  };
+
+  std::vector<Property> m_properties;
+  std::function<void()> m_safeState;
+  std::function<void()> m_updateTable;
+  std::shared_ptr<nt::NetworkTable> m_table;
+  nt::NetworkTableEntry m_controllableEntry;
+  bool m_actuator = false;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.h
new file mode 100644
index 0000000..6cf3c47
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.h
@@ -0,0 +1,68 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/StringMap.h>
+#include <wpi/StringRef.h>
+#include <wpi/deprecated.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableChooserBase.h"
+
+namespace frc {
+
+/**
+ * The SendableChooser class is a useful tool for presenting a selection of
+ * options to the SmartDashboard.
+ *
+ * For instance, you may wish to be able to select between multiple autonomous
+ * modes. You can do this by putting every possible Command you want to run as
+ * an autonomous into a SendableChooser and then put it into the SmartDashboard
+ * to have a list of options appear on the laptop. Once autonomous starts,
+ * simply ask the SendableChooser what the selected value is.
+ *
+ * @tparam T The type of values to be stored
+ * @see SmartDashboard
+ */
+template <class T>
+class SendableChooser : public SendableChooserBase {
+  wpi::StringMap<T> m_choices;
+
+  template <class U>
+  static U _unwrap_smart_ptr(const U& value);
+
+  template <class U>
+  static U* _unwrap_smart_ptr(const std::unique_ptr<U>& value);
+
+  template <class U>
+  static std::weak_ptr<U> _unwrap_smart_ptr(const std::shared_ptr<U>& value);
+
+ public:
+  ~SendableChooser() override = default;
+
+  void AddOption(wpi::StringRef name, T object);
+  void SetDefaultOption(wpi::StringRef name, T object);
+
+  WPI_DEPRECATED("use AddOption() instead")
+  void AddObject(wpi::StringRef name, T object) { AddOption(name, object); }
+
+  WPI_DEPRECATED("use SetDefaultOption() instead")
+  void AddDefault(wpi::StringRef name, T object) {
+    SetDefaultOption(name, object);
+  }
+
+  auto GetSelected() -> decltype(_unwrap_smart_ptr(m_choices[""]));
+
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
+
+#include "frc/smartdashboard/SendableChooser.inc"
diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.inc b/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.inc
new file mode 100644
index 0000000..295d263
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.inc
@@ -0,0 +1,142 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <algorithm>
+#include <memory>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include <wpi/StringRef.h>
+
+namespace frc {
+
+/**
+ * Adds the given object to the list of options.
+ *
+ * On the SmartDashboard on the desktop, the object will appear as the given
+ * name.
+ *
+ * @param name   the name of the option
+ * @param object the option
+ */
+template <class T>
+void SendableChooser<T>::AddOption(wpi::StringRef name, T object) {
+  m_choices[name] = std::move(object);
+}
+
+/**
+ * Add the given object to the list of options and marks it as the default.
+ *
+ * Functionally, this is very close to AddOption() except that it will use this
+ * as the default option if none other is explicitly selected.
+ *
+ * @param name   the name of the option
+ * @param object the option
+ */
+template <class T>
+void SendableChooser<T>::SetDefaultOption(wpi::StringRef name, T object) {
+  m_defaultChoice = name;
+  AddOption(name, std::move(object));
+}
+
+/**
+ * Returns a copy of the selected option (a raw pointer U* if T =
+ * std::unique_ptr<U> or a std::weak_ptr<U> if T = std::shared_ptr<U>).
+ *
+ * If there is none selected, it will return the default. If there is none
+ * selected and no default, then it will return a value-initialized instance.
+ * For integer types, this is 0. For container types like std::string, this is
+ * an empty string.
+ *
+ * @return The option selected
+ */
+template <class T>
+auto SendableChooser<T>::GetSelected()
+    -> decltype(_unwrap_smart_ptr(m_choices[""])) {
+  std::string selected = m_defaultChoice;
+  {
+    std::scoped_lock lock(m_mutex);
+    if (m_haveSelected) selected = m_selected;
+  }
+  if (selected.empty()) {
+    return decltype(_unwrap_smart_ptr(m_choices[""])){};
+  } else {
+    return _unwrap_smart_ptr(m_choices[selected]);
+  }
+}
+
+template <class T>
+void SendableChooser<T>::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("String Chooser");
+  builder.GetEntry(kInstance).SetDouble(m_instance);
+  builder.AddStringArrayProperty(kOptions,
+                                 [=]() {
+                                   std::vector<std::string> keys;
+                                   for (const auto& choice : m_choices) {
+                                     keys.push_back(choice.first());
+                                   }
+
+                                   // Unlike std::map, wpi::StringMap elements
+                                   // are not sorted
+                                   std::sort(keys.begin(), keys.end());
+
+                                   return keys;
+                                 },
+                                 nullptr);
+  builder.AddSmallStringProperty(
+      kDefault,
+      [=](wpi::SmallVectorImpl<char>&) -> wpi::StringRef {
+        return m_defaultChoice;
+      },
+      nullptr);
+  builder.AddSmallStringProperty(
+      kActive,
+      [=](wpi::SmallVectorImpl<char>& buf) -> wpi::StringRef {
+        std::scoped_lock lock(m_mutex);
+        if (m_haveSelected) {
+          buf.assign(m_selected.begin(), m_selected.end());
+          return wpi::StringRef(buf.data(), buf.size());
+        } else {
+          return m_defaultChoice;
+        }
+      },
+      nullptr);
+  {
+    std::scoped_lock lock(m_mutex);
+    m_activeEntries.emplace_back(builder.GetEntry(kActive));
+  }
+  builder.AddStringProperty(kSelected, nullptr, [=](wpi::StringRef val) {
+    std::scoped_lock lock(m_mutex);
+    m_haveSelected = true;
+    m_selected = val;
+    for (auto& entry : m_activeEntries) entry.SetString(val);
+  });
+}
+
+template <class T>
+template <class U>
+U SendableChooser<T>::_unwrap_smart_ptr(const U& value) {
+  return value;
+}
+
+template <class T>
+template <class U>
+U* SendableChooser<T>::_unwrap_smart_ptr(const std::unique_ptr<U>& value) {
+  return value.get();
+}
+
+template <class T>
+template <class U>
+std::weak_ptr<U> SendableChooser<T>::_unwrap_smart_ptr(
+    const std::shared_ptr<U>& value) {
+  return value;
+}
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooserBase.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooserBase.h
new file mode 100644
index 0000000..2a5f5ab
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooserBase.h
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+#include <string>
+
+#include <networktables/NetworkTableEntry.h>
+#include <wpi/SmallVector.h>
+#include <wpi/mutex.h>
+
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+/**
+ * This class is a non-template base class for SendableChooser.
+ *
+ * It contains static, non-templated variables to avoid their duplication in the
+ * template class.
+ */
+class SendableChooserBase : public Sendable,
+                            public SendableHelper<SendableChooserBase> {
+ public:
+  SendableChooserBase();
+  ~SendableChooserBase() override = default;
+
+  SendableChooserBase(SendableChooserBase&& oth);
+  SendableChooserBase& operator=(SendableChooserBase&& oth);
+
+ protected:
+  static constexpr const char* kDefault = "default";
+  static constexpr const char* kOptions = "options";
+  static constexpr const char* kSelected = "selected";
+  static constexpr const char* kActive = "active";
+  static constexpr const char* kInstance = ".instance";
+
+  std::string m_defaultChoice;
+  std::string m_selected;
+  bool m_haveSelected = false;
+  wpi::SmallVector<nt::NetworkTableEntry, 2> m_activeEntries;
+  wpi::mutex m_mutex;
+  int m_instance;
+  static std::atomic_int s_instances;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableHelper.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableHelper.h
new file mode 100644
index 0000000..6b0b28b
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableHelper.h
@@ -0,0 +1,161 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <wpi/Twine.h>
+#include <wpi/deprecated.h>
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+namespace frc {
+
+/**
+ * A helper class for use with objects that add themselves to SendableRegistry.
+ * It takes care of properly calling Move() and Remove() on move and
+ * destruction.  No action is taken if the object is copied.
+ * Use public inheritance with CRTP when using this class.
+ * @tparam CRTP derived class
+ */
+template <typename Derived>
+class SendableHelper {
+ public:
+  SendableHelper(const SendableHelper& rhs) = default;
+  SendableHelper& operator=(const SendableHelper& rhs) = default;
+
+  SendableHelper(SendableHelper&& rhs) {
+    // it is safe to call Move() multiple times with the same rhs
+    SendableRegistry::GetInstance().Move(static_cast<Derived*>(this),
+                                         static_cast<Derived*>(&rhs));
+  }
+
+  SendableHelper& operator=(SendableHelper&& rhs) {
+    // it is safe to call Move() multiple times with the same rhs
+    SendableRegistry::GetInstance().Move(static_cast<Derived*>(this),
+                                         static_cast<Derived*>(&rhs));
+    return *this;
+  }
+
+  /**
+   * Gets the name of this Sendable object.
+   *
+   * @return Name
+   */
+  WPI_DEPRECATED("use SendableRegistry::GetName()")
+  std::string GetName() const {
+    return SendableRegistry::GetInstance().GetName(
+        static_cast<const Derived*>(this));
+  }
+
+  /**
+   * Sets the name of this Sendable object.
+   *
+   * @param name name
+   */
+  WPI_DEPRECATED("use SendableRegistry::SetName()")
+  void SetName(const wpi::Twine& name) {
+    SendableRegistry::GetInstance().SetName(static_cast<Derived*>(this), name);
+  }
+
+  /**
+   * Sets both the subsystem name and device name of this Sendable object.
+   *
+   * @param subsystem subsystem name
+   * @param name device name
+   */
+  WPI_DEPRECATED("use SendableRegistry::SetName()")
+  void SetName(const wpi::Twine& subsystem, const wpi::Twine& name) {
+    SendableRegistry::GetInstance().SetName(static_cast<Derived*>(this),
+                                            subsystem, name);
+  }
+
+  /**
+   * Gets the subsystem name of this Sendable object.
+   *
+   * @return Subsystem name
+   */
+  WPI_DEPRECATED("use SendableRegistry::GetSubsystem()")
+  std::string GetSubsystem() const {
+    return SendableRegistry::GetInstance().GetSubsystem(
+        static_cast<const Derived*>(this));
+  }
+
+  /**
+   * Sets the subsystem name of this Sendable object.
+   *
+   * @param subsystem subsystem name
+   */
+  WPI_DEPRECATED("use SendableRegistry::SetSubsystem()")
+  void SetSubsystem(const wpi::Twine& subsystem) {
+    SendableRegistry::GetInstance().SetSubsystem(static_cast<Derived*>(this),
+                                                 subsystem);
+  }
+
+ protected:
+  /**
+   * Add a child component.
+   *
+   * @param child child component
+   */
+  WPI_DEPRECATED("use SendableRegistry::AddChild()")
+  void AddChild(std::shared_ptr<Sendable> child) {
+    SendableRegistry::GetInstance().AddChild(static_cast<Derived*>(this),
+                                             child.get());
+  }
+
+  /**
+   * Add a child component.
+   *
+   * @param child child component
+   */
+  WPI_DEPRECATED("use SendableRegistry::AddChild()")
+  void AddChild(void* child) {
+    SendableRegistry::GetInstance().AddChild(static_cast<Derived*>(this),
+                                             child);
+  }
+
+  /**
+   * Sets the name of the sensor with a channel number.
+   *
+   * @param moduleType A string that defines the module name in the label for
+   *                   the value
+   * @param channel    The channel number the device is plugged into
+   */
+  WPI_DEPRECATED("use SendableRegistry::SetName()")
+  void SetName(const wpi::Twine& moduleType, int channel) {
+    SendableRegistry::GetInstance().SetName(static_cast<Derived*>(this),
+                                            moduleType, channel);
+  }
+
+  /**
+   * Sets the name of the sensor with a module and channel number.
+   *
+   * @param moduleType   A string that defines the module name in the label for
+   *                     the value
+   * @param moduleNumber The number of the particular module type
+   * @param channel      The channel number the device is plugged into (usually
+   * PWM)
+   */
+  WPI_DEPRECATED("use SendableRegistry::SetName()")
+  void SetName(const wpi::Twine& moduleType, int moduleNumber, int channel) {
+    SendableRegistry::GetInstance().SetName(static_cast<Derived*>(this),
+                                            moduleType, moduleNumber, channel);
+  }
+
+ protected:
+  SendableHelper() = default;
+
+  ~SendableHelper() {
+    // it is safe to call Remove() multiple times with the same object
+    SendableRegistry::GetInstance().Remove(static_cast<Derived*>(this));
+  }
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableRegistry.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableRegistry.h
new file mode 100644
index 0000000..78dabc6
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableRegistry.h
@@ -0,0 +1,341 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <networktables/NetworkTable.h>
+#include <wpi/STLExtras.h>
+#include <wpi/Twine.h>
+
+namespace frc {
+
+class Sendable;
+class SendableBuilderImpl;
+
+/**
+ * The SendableRegistry class is the public interface for registering sensors
+ * and actuators for use on dashboards and LiveWindow.
+ */
+class SendableRegistry {
+ public:
+  SendableRegistry(const SendableRegistry&) = delete;
+  SendableRegistry& operator=(const SendableRegistry&) = delete;
+
+  using UID = size_t;
+
+  /**
+   * Gets an instance of the SendableRegistry class.
+   *
+   * This is a singleton to guarantee that there is only a single instance
+   * regardless of how many times GetInstance is called.
+   */
+  static SendableRegistry& GetInstance();
+
+  /**
+   * Adds an object to the registry.
+   *
+   * @param sendable object to add
+   * @param name component name
+   */
+  void Add(Sendable* sendable, const wpi::Twine& name);
+
+  /**
+   * Adds an object to the registry.
+   *
+   * @param sendable     object to add
+   * @param moduleType   A string that defines the module name in the label for
+   *                     the value
+   * @param channel      The channel number the device is plugged into
+   */
+  void Add(Sendable* sendable, const wpi::Twine& moduleType, int channel);
+
+  /**
+   * Adds an object to the registry.
+   *
+   * @param sendable     object to add
+   * @param moduleType   A string that defines the module name in the label for
+   *                     the value
+   * @param moduleNumber The number of the particular module type
+   * @param channel      The channel number the device is plugged into
+   */
+  void Add(Sendable* sendable, const wpi::Twine& moduleType, int moduleNumber,
+           int channel);
+
+  /**
+   * Adds an object to the registry.
+   *
+   * @param sendable object to add
+   * @param subsystem subsystem name
+   * @param name component name
+   */
+  void Add(Sendable* sendable, const wpi::Twine& subsystem,
+           const wpi::Twine& name);
+
+  /**
+   * Adds an object to the registry and LiveWindow.
+   *
+   * @param sendable object to add
+   * @param name component name
+   */
+  void AddLW(Sendable* sendable, const wpi::Twine& name);
+
+  /**
+   * Adds an object to the registry and LiveWindow.
+   *
+   * @param sendable     object to add
+   * @param moduleType   A string that defines the module name in the label for
+   *                     the value
+   * @param channel      The channel number the device is plugged into
+   */
+  void AddLW(Sendable* sendable, const wpi::Twine& moduleType, int channel);
+
+  /**
+   * Adds an object to the registry and LiveWindow.
+   *
+   * @param sendable     object to add
+   * @param moduleType   A string that defines the module name in the label for
+   *                     the value
+   * @param moduleNumber The number of the particular module type
+   * @param channel      The channel number the device is plugged into
+   */
+  void AddLW(Sendable* sendable, const wpi::Twine& moduleType, int moduleNumber,
+             int channel);
+
+  /**
+   * Adds an object to the registry and LiveWindow.
+   *
+   * @param sendable object to add
+   * @param subsystem subsystem name
+   * @param name component name
+   */
+  void AddLW(Sendable* sendable, const wpi::Twine& subsystem,
+             const wpi::Twine& name);
+
+  /**
+   * Adds a child object to an object.  Adds the child object to the registry
+   * if it's not already present.
+   *
+   * @param parent parent object
+   * @param child child object
+   */
+  void AddChild(Sendable* parent, Sendable* child);
+
+  /**
+   * Adds a child object to an object.  Adds the child object to the registry
+   * if it's not already present.
+   *
+   * @param parent parent object
+   * @param child child object
+   */
+  void AddChild(Sendable* parent, void* child);
+
+  /**
+   * Removes an object from the registry.
+   *
+   * @param sendable object to remove
+   * @return true if the object was removed; false if it was not present
+   */
+  bool Remove(Sendable* sendable);
+
+  /**
+   * Moves an object in the registry (for use in move constructors/assignments).
+   *
+   * @param to new object
+   * @param from old object
+   */
+  void Move(Sendable* to, Sendable* from);
+
+  /**
+   * Determines if an object is in the registry.
+   *
+   * @param sendable object to check
+   * @return True if in registry, false if not.
+   */
+  bool Contains(const Sendable* sendable) const;
+
+  /**
+   * Gets the name of an object.
+   *
+   * @param sendable object
+   * @return Name (empty if object is not in registry)
+   */
+  std::string GetName(const Sendable* sendable) const;
+
+  /**
+   * Sets the name of an object.
+   *
+   * @param sendable object
+   * @param name name
+   */
+  void SetName(Sendable* sendable, const wpi::Twine& name);
+
+  /**
+   * Sets the name of an object with a channel number.
+   *
+   * @param sendable   object
+   * @param moduleType A string that defines the module name in the label for
+   *                   the value
+   * @param channel    The channel number the device is plugged into
+   */
+  void SetName(Sendable* sendable, const wpi::Twine& moduleType, int channel);
+
+  /**
+   * Sets the name of an object with a module and channel number.
+   *
+   * @param sendable     object
+   * @param moduleType   A string that defines the module name in the label for
+   *                     the value
+   * @param moduleNumber The number of the particular module type
+   * @param channel      The channel number the device is plugged into
+   */
+  void SetName(Sendable* sendable, const wpi::Twine& moduleType,
+               int moduleNumber, int channel);
+
+  /**
+   * Sets both the subsystem name and device name of an object.
+   *
+   * @param sendable object
+   * @param subsystem subsystem name
+   * @param name device name
+   */
+  void SetName(Sendable* sendable, const wpi::Twine& subsystem,
+               const wpi::Twine& name);
+
+  /**
+   * Gets the subsystem name of an object.
+   *
+   * @param sendable object
+   * @return Subsystem name (empty if object is not in registry)
+   */
+  std::string GetSubsystem(const Sendable* sendable) const;
+
+  /**
+   * Sets the subsystem name of an object.
+   *
+   * @param sendable object
+   * @param subsystem subsystem name
+   */
+  void SetSubsystem(Sendable* sendable, const wpi::Twine& subsystem);
+
+  /**
+   * Gets a unique handle for setting/getting data with SetData() and GetData().
+   *
+   * @return Handle
+   */
+  int GetDataHandle();
+
+  /**
+   * Associates arbitrary data with an object in the registry.
+   *
+   * @param sendable object
+   * @param handle data handle returned by GetDataHandle()
+   * @param data data to set
+   * @return Previous data (may be null)
+   */
+  std::shared_ptr<void> SetData(Sendable* sendable, int handle,
+                                std::shared_ptr<void> data);
+
+  /**
+   * Gets arbitrary data associated with an object in the registry.
+   *
+   * @param sendable object
+   * @param handle data handle returned by GetDataHandle()
+   * @return data (may be null if none associated)
+   */
+  std::shared_ptr<void> GetData(Sendable* sendable, int handle);
+
+  /**
+   * Enables LiveWindow for an object.
+   *
+   * @param sendable object
+   */
+  void EnableLiveWindow(Sendable* sendable);
+
+  /**
+   * Disables LiveWindow for an object.
+   *
+   * @param sendable object
+   */
+  void DisableLiveWindow(Sendable* sendable);
+
+  /**
+   * Get unique id for an object.  Since objects can move, use this instead
+   * of storing Sendable* directly if ownership is in question.
+   *
+   * @param sendable object
+   * @return unique id
+   */
+  UID GetUniqueId(Sendable* sendable);
+
+  /**
+   * Get sendable object for a given unique id.
+   *
+   * @param uid unique id
+   * @return sendable object (may be null)
+   */
+  Sendable* GetSendable(UID uid);
+
+  /**
+   * Publishes an object in the registry to a network table.
+   *
+   * @param sendableUid sendable unique id
+   * @param table network table
+   */
+  void Publish(UID sendableUid, std::shared_ptr<NetworkTable> table);
+
+  /**
+   * Updates network table information from an object.
+   *
+   * @param sendableUid sendable unique id
+   */
+  void Update(UID sendableUid);
+
+  /**
+   * Data passed to ForeachLiveWindow() callback function
+   */
+  struct CallbackData {
+    CallbackData(Sendable* sendable_, wpi::StringRef name_,
+                 wpi::StringRef subsystem_, Sendable* parent_,
+                 std::shared_ptr<void>& data_, SendableBuilderImpl& builder_)
+        : sendable(sendable_),
+          name(name_),
+          subsystem(subsystem_),
+          parent(parent_),
+          data(data_),
+          builder(builder_) {}
+
+    Sendable* sendable;
+    wpi::StringRef name;
+    wpi::StringRef subsystem;
+    Sendable* parent;
+    std::shared_ptr<void>& data;
+    SendableBuilderImpl& builder;
+  };
+
+  /**
+   * Iterates over LiveWindow-enabled objects in the registry.
+   * It is *not* safe to call other SendableRegistry functions from the
+   * callback (this will likely deadlock).
+   *
+   * @param dataHandle data handle to get data pointer passed to callback
+   * @param callback function to call for each object
+   */
+  void ForeachLiveWindow(
+      int dataHandle,
+      wpi::function_ref<void(CallbackData& cbdata)> callback) const;
+
+ private:
+  SendableRegistry();
+
+  struct Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h b/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h
new file mode 100644
index 0000000..9fdc049
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h
@@ -0,0 +1,443 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableValue.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/ListenerExecutor.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+class SmartDashboard : public ErrorBase,
+                       public Sendable,
+                       public SendableHelper<SmartDashboard> {
+ public:
+  static void init();
+
+  /**
+   * Determines whether the given key is in this table.
+   *
+   * @param key the key to search for
+   * @return true if the table as a value assigned to the given key
+   */
+  static bool ContainsKey(wpi::StringRef key);
+
+  /**
+   * @param types bitmask of types; 0 is treated as a "don't care".
+   * @return keys currently in the table
+   */
+  static std::vector<std::string> GetKeys(int types = 0);
+
+  /**
+   * Makes a key's value persistent through program restarts.
+   *
+   * @param key the key to make persistent
+   */
+  static void SetPersistent(wpi::StringRef key);
+
+  /**
+   * Stop making a key's value persistent through program restarts.
+   * The key cannot be null.
+   *
+   * @param key the key name
+   */
+  static void ClearPersistent(wpi::StringRef key);
+
+  /**
+   * Returns whether the value is persistent through program restarts.
+   * The key cannot be null.
+   *
+   * @param key the key name
+   */
+  static bool IsPersistent(wpi::StringRef key);
+
+  /**
+   * Sets flags on the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   * @param flags the flags to set (bitmask)
+   */
+  static void SetFlags(wpi::StringRef key, unsigned int flags);
+
+  /**
+   * Clears flags on the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   * @param flags the flags to clear (bitmask)
+   */
+  static void ClearFlags(wpi::StringRef key, unsigned int flags);
+
+  /**
+   * Returns the flags for the specified key.
+   *
+   * @param key the key name
+   * @return the flags, or 0 if the key is not defined
+   */
+  static unsigned int GetFlags(wpi::StringRef key);
+
+  /**
+   * Deletes the specified key in this table.
+   *
+   * @param key the key name
+   */
+  static void Delete(wpi::StringRef key);
+
+  /**
+   * Returns an NT Entry mapping to the specified key
+   *
+   * This is useful if an entry is used often, or is read and then modified.
+   *
+   * @param key the key
+   * @return    the entry for the key
+   */
+  static nt::NetworkTableEntry GetEntry(wpi::StringRef key);
+
+  /**
+   * Maps the specified key to the specified value in this table.
+   *
+   * The value can be retrieved by calling the get method with a key that is
+   * equal to the original key.
+   *
+   * In order for the value to appear in the dashboard, it must be registered
+   * with SendableRegistry.  WPILib components do this automatically.
+   *
+   * @param keyName the key
+   * @param value   the value
+   */
+  static void PutData(wpi::StringRef key, Sendable* data);
+
+  /**
+   * Maps the specified key (where the key is the name of the Sendable)
+   * to the specified value in this table.
+   *
+   * The value can be retrieved by calling the get method with a key that is
+   * equal to the original key.
+   *
+   * In order for the value to appear in the dashboard, it must be registered
+   * with SendableRegistry.  WPILib components do this automatically.
+   *
+   * @param value the value
+   */
+  static void PutData(Sendable* value);
+
+  /**
+   * Returns the value at the specified key.
+   *
+   * @param keyName the key
+   * @return the value
+   */
+  static Sendable* GetData(wpi::StringRef keyName);
+
+  /**
+   * Maps the specified key to the specified value in this table.
+   *
+   * The value can be retrieved by calling the get method with a key that is
+   * equal to the original key.
+   *
+   * @param keyName the key
+   * @param value   the value
+   * @return        False if the table key already exists with a different type
+   */
+  static bool PutBoolean(wpi::StringRef keyName, bool value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultBoolean(wpi::StringRef key, bool defaultValue);
+
+  /**
+   * Returns the value at the specified key.
+   *
+   * If the key is not found, returns the default value.
+   *
+   * @param keyName the key
+   * @return the value
+   */
+  static bool GetBoolean(wpi::StringRef keyName, bool defaultValue);
+
+  /**
+   * Maps the specified key to the specified value in this table.
+   *
+   * The value can be retrieved by calling the get method with a key that is
+   * equal to the original key.
+   *
+   * @param keyName the key
+   * @param value   the value
+   * @return        False if the table key already exists with a different type
+   */
+  static bool PutNumber(wpi::StringRef keyName, double value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key          The key.
+   * @param defaultValue The default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultNumber(wpi::StringRef key, double defaultValue);
+
+  /**
+   * Returns the value at the specified key.
+   *
+   * If the key is not found, returns the default value.
+   *
+   * @param keyName the key
+   * @return the value
+   */
+  static double GetNumber(wpi::StringRef keyName, double defaultValue);
+
+  /**
+   * Maps the specified key to the specified value in this table.
+   *
+   * The value can be retrieved by calling the get method with a key that is
+   * equal to the original key.
+   *
+   * @param keyName the key
+   * @param value   the value
+   * @return        False if the table key already exists with a different type
+   */
+  static bool PutString(wpi::StringRef keyName, wpi::StringRef value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultString(wpi::StringRef key, wpi::StringRef defaultValue);
+
+  /**
+   * Returns the value at the specified key.
+   *
+   * If the key is not found, returns the default value.
+   *
+   * @param keyName the key
+   * @return the value
+   */
+  static std::string GetString(wpi::StringRef keyName,
+                               wpi::StringRef defaultValue);
+
+  /**
+   * Put a boolean array in the table.
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   *
+   * @note The array must be of int's rather than of bool's because
+   *       std::vector<bool> is special-cased in C++. 0 is false, any
+   *       non-zero value is true.
+   */
+  static bool PutBooleanArray(wpi::StringRef key, wpi::ArrayRef<int> value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultBooleanArray(wpi::StringRef key,
+                                     wpi::ArrayRef<int> defaultValue);
+
+  /**
+   * Returns the boolean array the key maps to.
+   *
+   * If the key does not exist or is of different type, it will return the
+   * default value.
+   *
+   * @param key          The key to look up.
+   * @param defaultValue The value to be returned if no value is found.
+   * @return the value associated with the given key or the given default value
+   *         if there is no value associated with the key
+   *
+   * @note This makes a copy of the array. If the overhead of this is a concern,
+   *       use GetValue() instead.
+   *
+   * @note The returned array is std::vector<int> instead of std::vector<bool>
+   *       because std::vector<bool> is special-cased in C++. 0 is false, any
+   *       non-zero value is true.
+   */
+  static std::vector<int> GetBooleanArray(wpi::StringRef key,
+                                          wpi::ArrayRef<int> defaultValue);
+
+  /**
+   * Put a number array in the table.
+   *
+   * @param key   The key to be assigned to.
+   * @param value The value that will be assigned.
+   * @return False if the table key already exists with a different type
+   */
+  static bool PutNumberArray(wpi::StringRef key, wpi::ArrayRef<double> value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key          The key.
+   * @param defaultValue The default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultNumberArray(wpi::StringRef key,
+                                    wpi::ArrayRef<double> defaultValue);
+
+  /**
+   * Returns the number array the key maps to.
+   *
+   * If the key does not exist or is of different type, it will return the
+   * default value.
+   *
+   * @param key The key to look up.
+   * @param defaultValue The value to be returned if no value is found.
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   *
+   * @note This makes a copy of the array. If the overhead of this is a concern,
+   *       use GetValue() instead.
+   */
+  static std::vector<double> GetNumberArray(wpi::StringRef key,
+                                            wpi::ArrayRef<double> defaultValue);
+
+  /**
+   * Put a string array in the table.
+   *
+   * @param key   The key to be assigned to.
+   * @param value The value that will be assigned.
+   * @return False if the table key already exists with a different type
+   */
+  static bool PutStringArray(wpi::StringRef key,
+                             wpi::ArrayRef<std::string> value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key          The key.
+   * @param defaultValue The default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultStringArray(wpi::StringRef key,
+                                    wpi::ArrayRef<std::string> defaultValue);
+
+  /**
+   * Returns the string array the key maps to.
+   *
+   * If the key does not exist or is of different type, it will return the
+   * default value.
+   *
+   * @param key          The key to look up.
+   * @param defaultValue The value to be returned if no value is found.
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   *
+   * @note This makes a copy of the array. If the overhead of this is a concern,
+   *       use GetValue() instead.
+   */
+  static std::vector<std::string> GetStringArray(
+      wpi::StringRef key, wpi::ArrayRef<std::string> defaultValue);
+
+  /**
+   * Put a raw value (byte array) in the table.
+   *
+   * @param key   The key to be assigned to.
+   * @param value The value that will be assigned.
+   * @return False if the table key already exists with a different type
+   */
+  static bool PutRaw(wpi::StringRef key, wpi::StringRef value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key          The key.
+   * @param defaultValue The default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultRaw(wpi::StringRef key, wpi::StringRef defaultValue);
+
+  /**
+   * Returns the raw value (byte array) the key maps to.
+   *
+   * If the key does not exist or is of different type, it will return the
+   * default value.
+   *
+   * @param key          The key to look up.
+   * @param defaultValue The value to be returned if no value is found.
+   * @return the value associated with the given key or the given default value
+   *         if there is no value associated with the key
+   *
+   * @note This makes a copy of the raw contents. If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  static std::string GetRaw(wpi::StringRef key, wpi::StringRef defaultValue);
+
+  /**
+   * Maps the specified key to the specified complex value (such as an array) in
+   * this table.
+   *
+   * The value can be retrieved by calling the RetrieveValue method with a key
+   * that is equal to the original key.
+   *
+   * @param keyName the key
+   * @param value   the value
+   * @return        False if the table key already exists with a different type
+   */
+  static bool PutValue(wpi::StringRef keyName,
+                       std::shared_ptr<nt::Value> value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue The default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultValue(wpi::StringRef key,
+                              std::shared_ptr<nt::Value> defaultValue);
+
+  /**
+   * Retrieves the complex value (such as an array) in this table into the
+   * complex data object.
+   *
+   * @param keyName the key
+   * @param value   the object to retrieve the value into
+   */
+  static std::shared_ptr<nt::Value> GetValue(wpi::StringRef keyName);
+
+  /**
+   * Posts a task from a listener to the ListenerExecutor, so that it can be run
+   * synchronously from the main loop on the next call to {@link
+   * SmartDashboard#updateValues()}.
+   *
+   * @param task The task to run synchronously from the main thread.
+   */
+  static void PostListenerTask(std::function<void()> task);
+
+  /**
+   * Puts all sendable data to the dashboard.
+   */
+  static void UpdateValues();
+
+ private:
+  virtual ~SmartDashboard() = default;
+
+  static detail::ListenerExecutor listenerExecutor;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/spline/CubicHermiteSpline.h b/wpilibc/src/main/native/include/frc/spline/CubicHermiteSpline.h
new file mode 100644
index 0000000..1e08a94
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/spline/CubicHermiteSpline.h
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <array>
+
+#include <Eigen/Core>
+
+#include "frc/spline/Spline.h"
+
+namespace frc {
+/**
+ * Represents a hermite spline of degree 3.
+ */
+class CubicHermiteSpline : public Spline<3> {
+ public:
+  /**
+   * Constructs a cubic hermite spline with the specified control vectors. Each
+   * control vector contains info about the location of the point and its first
+   * derivative.
+   *
+   * @param xInitialControlVector The control vector for the initial point in
+   * the x dimension.
+   * @param xFinalControlVector The control vector for the final point in
+   * the x dimension.
+   * @param yInitialControlVector The control vector for the initial point in
+   * the y dimension.
+   * @param yFinalControlVector The control vector for the final point in
+   * the y dimension.
+   */
+  CubicHermiteSpline(std::array<double, 2> xInitialControlVector,
+                     std::array<double, 2> xFinalControlVector,
+                     std::array<double, 2> yInitialControlVector,
+                     std::array<double, 2> yFinalControlVector);
+
+ protected:
+  /**
+   * Returns the coefficients matrix.
+   * @return The coefficients matrix.
+   */
+  Eigen::Matrix<double, 6, 3 + 1> Coefficients() const override {
+    return m_coefficients;
+  }
+
+ private:
+  Eigen::Matrix<double, 6, 4> m_coefficients =
+      Eigen::Matrix<double, 6, 4>::Zero();
+
+  /**
+   * Returns the hermite basis matrix for cubic hermite spline interpolation.
+   * @return The hermite basis matrix for cubic hermite spline interpolation.
+   */
+  static Eigen::Matrix<double, 4, 4> MakeHermiteBasis() {
+    // clang-format off
+    static auto basis = (Eigen::Matrix<double, 4, 4>() <<
+     +2.0, +1.0, -2.0, +1.0,
+     -3.0, -2.0, +3.0, -1.0,
+     +0.0, +1.0, +0.0, +0.0,
+     +1.0, +0.0, +0.0, +0.0).finished();
+    // clang-format on
+    return basis;
+  }
+
+  /**
+   * Returns the control vector for each dimension as a matrix from the
+   * user-provided arrays in the constructor.
+   *
+   * @param initialVector The control vector for the initial point.
+   * @param finalVector The control vector for the final point.
+   *
+   * @return The control vector matrix for a dimension.
+   */
+  static Eigen::Vector4d ControlVectorFromArrays(
+      std::array<double, 2> initialVector, std::array<double, 2> finalVector) {
+    return (Eigen::Vector4d() << initialVector[0], initialVector[1],
+            finalVector[0], finalVector[1])
+        .finished();
+  }
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/spline/QuinticHermiteSpline.h b/wpilibc/src/main/native/include/frc/spline/QuinticHermiteSpline.h
new file mode 100644
index 0000000..632d3ad
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/spline/QuinticHermiteSpline.h
@@ -0,0 +1,87 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <array>
+
+#include <Eigen/Core>
+
+#include "frc/spline/Spline.h"
+
+namespace frc {
+/**
+ * Represents a hermite spline of degree 5.
+ */
+class QuinticHermiteSpline : public Spline<5> {
+ public:
+  /**
+   * Constructs a quintic hermite spline with the specified control vectors.
+   * Each control vector contains into about the location of the point, its
+   * first derivative, and its second derivative.
+   *
+   * @param xInitialControlVector The control vector for the initial point in
+   * the x dimension.
+   * @param xFinalControlVector The control vector for the final point in
+   * the x dimension.
+   * @param yInitialControlVector The control vector for the initial point in
+   * the y dimension.
+   * @param yFinalControlVector The control vector for the final point in
+   * the y dimension.
+   */
+  QuinticHermiteSpline(std::array<double, 3> xInitialControlVector,
+                       std::array<double, 3> xFinalControlVector,
+                       std::array<double, 3> yInitialControlVector,
+                       std::array<double, 3> yFinalControlVector);
+
+ protected:
+  /**
+   * Returns the coefficients matrix.
+   * @return The coefficients matrix.
+   */
+  Eigen::Matrix<double, 6, 6> Coefficients() const override {
+    return m_coefficients;
+  }
+
+ private:
+  Eigen::Matrix<double, 6, 6> m_coefficients =
+      Eigen::Matrix<double, 6, 6>::Zero();
+
+  /**
+   * Returns the hermite basis matrix for quintic hermite spline interpolation.
+   * @return The hermite basis matrix for quintic hermite spline interpolation.
+   */
+  static Eigen::Matrix<double, 6, 6> MakeHermiteBasis() {
+    // clang-format off
+    static const auto basis = (Eigen::Matrix<double, 6, 6>() <<
+      -06.0, -03.0, -00.5, +06.0, -03.0, +00.5,
+      +15.0, +08.0, +01.5, -15.0, +07.0, +01.0,
+      -10.0, -06.0, -01.5, +10.0, -04.0, +00.5,
+      +00.0, +00.0, +00.5, +00.0, +00.0, +00.0,
+      +00.0, +01.0, +00.0, +00.0, +00.0, +00.0,
+      +01.0, +00.0, +00.0, +00.0, +00.0, +00.0).finished();
+    // clang-format on
+    return basis;
+  }
+
+  /**
+   * Returns the control vector for each dimension as a matrix from the
+   * user-provided arrays in the constructor.
+   *
+   * @param initialVector The control vector for the initial point.
+   * @param finalVector The control vector for the final point.
+   *
+   * @return The control vector matrix for a dimension.
+   */
+  static Eigen::Matrix<double, 6, 1> ControlVectorFromArrays(
+      std::array<double, 3> initialVector, std::array<double, 3> finalVector) {
+    return (Eigen::Matrix<double, 6, 1>() << initialVector[0], initialVector[1],
+            initialVector[2], finalVector[0], finalVector[1], finalVector[2])
+        .finished();
+  }
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/spline/Spline.h b/wpilibc/src/main/native/include/frc/spline/Spline.h
new file mode 100644
index 0000000..e8f2372
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/spline/Spline.h
@@ -0,0 +1,135 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <array>
+#include <utility>
+#include <vector>
+
+#include <Eigen/Core>
+
+#include "frc/geometry/Pose2d.h"
+
+namespace frc {
+
+/**
+ * Define a unit for curvature.
+ */
+using curvature_t = units::unit_t<
+    units::compound_unit<units::radian, units::inverse<units::meter>>>;
+
+/**
+ * Represents a two-dimensional parametric spline that interpolates between two
+ * points.
+ *
+ * @tparam Degree The degree of the spline.
+ */
+template <int Degree>
+class Spline {
+ public:
+  using PoseWithCurvature = std::pair<Pose2d, curvature_t>;
+
+  Spline() = default;
+
+  Spline(const Spline&) = default;
+  Spline& operator=(const Spline&) = default;
+
+  Spline(Spline&&) = default;
+  Spline& operator=(Spline&&) = default;
+
+  virtual ~Spline() = default;
+
+  /**
+   * Represents a control vector for a spline.
+   *
+   * Each element in each array represents the value of the derivative at the
+   * index. For example, the value of x[2] is the second derivative in the x
+   * dimension.
+   */
+  struct ControlVector {
+    std::array<double, (Degree + 1) / 2> x;
+    std::array<double, (Degree + 1) / 2> y;
+  };
+
+  /**
+   * Gets the pose and curvature at some point t on the spline.
+   *
+   * @param t The point t
+   * @return The pose and curvature at that point.
+   */
+  PoseWithCurvature GetPoint(double t) const {
+    Eigen::Matrix<double, Degree + 1, 1> polynomialBases;
+
+    // Populate the polynomial bases
+    for (int i = 0; i <= Degree; i++) {
+      polynomialBases(i) = std::pow(t, Degree - i);
+    }
+
+    // This simply multiplies by the coefficients. We need to divide out t some
+    // n number of times where n is the derivative we want to take.
+    Eigen::Matrix<double, 6, 1> combined = Coefficients() * polynomialBases;
+
+    double dx, dy, ddx, ddy;
+
+    // If t = 0, all other terms in the equation cancel out to zero. We can use
+    // the last x^0 term in the equation.
+    if (t == 0.0) {
+      dx = Coefficients()(2, Degree - 1);
+      dy = Coefficients()(3, Degree - 1);
+      ddx = Coefficients()(4, Degree - 2);
+      ddy = Coefficients()(5, Degree - 2);
+    } else {
+      // Divide out t for first derivative.
+      dx = combined(2) / t;
+      dy = combined(3) / t;
+
+      // Divide out t for second derivative.
+      ddx = combined(4) / t / t;
+      ddy = combined(5) / t / t;
+    }
+
+    // Find the curvature.
+    const auto curvature =
+        (dx * ddy - ddx * dy) / ((dx * dx + dy * dy) * std::hypot(dx, dy));
+
+    return {
+        {FromVector(combined.template block<2, 1>(0, 0)), Rotation2d(dx, dy)},
+        curvature_t(curvature)};
+  }
+
+ protected:
+  /**
+   * Returns the coefficients of the spline.
+   *
+   * @return The coefficients of the spline.
+   */
+  virtual Eigen::Matrix<double, 6, Degree + 1> Coefficients() const = 0;
+
+  /**
+   * Converts a Translation2d into a vector that is compatible with Eigen.
+   *
+   * @param translation The Translation2d to convert.
+   * @return The vector.
+   */
+  static Eigen::Vector2d ToVector(const Translation2d& translation) {
+    return (Eigen::Vector2d() << translation.X().to<double>(),
+            translation.Y().to<double>())
+        .finished();
+  }
+
+  /**
+   * Converts an Eigen vector into a Translation2d.
+   *
+   * @param vector The vector to convert.
+   * @return The Translation2d.
+   */
+  static Translation2d FromVector(const Eigen::Vector2d& vector) {
+    return Translation2d(units::meter_t(vector(0)), units::meter_t(vector(1)));
+  }
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/spline/SplineHelper.h b/wpilibc/src/main/native/include/frc/spline/SplineHelper.h
new file mode 100644
index 0000000..4ed1cf5
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/spline/SplineHelper.h
@@ -0,0 +1,113 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <array>
+#include <utility>
+#include <vector>
+
+#include "frc/spline/CubicHermiteSpline.h"
+#include "frc/spline/QuinticHermiteSpline.h"
+
+namespace frc {
+/**
+ * Helper class that is used to generate cubic and quintic splines from user
+ * provided waypoints.
+ */
+class SplineHelper {
+ public:
+  /**
+   * Returns 2 cubic control vectors from a set of exterior waypoints and
+   * interior translations.
+   *
+   * @param start             The starting pose.
+   * @param interiorWaypoints The interior waypoints.
+   * @param end               The ending pose.
+   * @return 2 cubic control vectors.
+   */
+  static std::array<Spline<3>::ControlVector, 2>
+  CubicControlVectorsFromWaypoints(
+      const Pose2d& start, const std::vector<Translation2d>& interiorWaypoints,
+      const Pose2d& end);
+
+  /**
+   * Returns quintic control vectors from a set of waypoints.
+   *
+   * @param waypoints The waypoints
+   * @return List of control vectors
+   */
+  static std::vector<Spline<5>::ControlVector>
+  QuinticControlVectorsFromWaypoints(const std::vector<Pose2d>& waypoints);
+
+  /**
+   * Returns a set of cubic splines corresponding to the provided control
+   * vectors. The user is free to set the direction of the start and end
+   * point. The directions for the middle waypoints are determined
+   * automatically to ensure continuous curvature throughout the path.
+   *
+   * The derivation for the algorithm used can be found here:
+   * <https://www.uio.no/studier/emner/matnat/ifi/nedlagte-emner/INF-MAT4350/h08/undervisningsmateriale/chap7alecture.pdf>
+   *
+   * @param start The starting control vector.
+   * @param waypoints The middle waypoints. This can be left blank if you
+   * only wish to create a path with two waypoints.
+   * @param end The ending control vector.
+   *
+   * @return A vector of cubic hermite splines that interpolate through the
+   * provided waypoints.
+   */
+  static std::vector<CubicHermiteSpline> CubicSplinesFromControlVectors(
+      const Spline<3>::ControlVector& start,
+      std::vector<Translation2d> waypoints,
+      const Spline<3>::ControlVector& end);
+
+  /**
+   * Returns a set of quintic splines corresponding to the provided control
+   * vectors. The user is free to set the direction of all waypoints. Continuous
+   * curvature is guaranteed throughout the path.
+   *
+   * @param controlVectors The control vectors.
+   * @return A vector of quintic hermite splines that interpolate through the
+   * provided waypoints.
+   */
+  static std::vector<QuinticHermiteSpline> QuinticSplinesFromControlVectors(
+      const std::vector<Spline<5>::ControlVector>& controlVectors);
+
+ private:
+  static Spline<3>::ControlVector CubicControlVector(double scalar,
+                                                     const Pose2d& point) {
+    return {
+        {point.Translation().X().to<double>(), scalar * point.Rotation().Cos()},
+        {point.Translation().Y().to<double>(),
+         scalar * point.Rotation().Sin()}};
+  }
+
+  static Spline<5>::ControlVector QuinticControlVector(double scalar,
+                                                       const Pose2d& point) {
+    return {{point.Translation().X().to<double>(),
+             scalar * point.Rotation().Cos(), 0.0},
+            {point.Translation().Y().to<double>(),
+             scalar * point.Rotation().Sin(), 0.0}};
+  }
+
+  /**
+   * Thomas algorithm for solving tridiagonal systems Af = d.
+   *
+   * @param a the values of A above the diagonal
+   * @param b the values of A on the diagonal
+   * @param c the values of A below the diagonal
+   * @param d the vector on the rhs
+   * @param solutionVector the unknown (solution) vector, modified in-place
+   */
+  static void ThomasAlgorithm(const std::vector<double>& a,
+                              const std::vector<double>& b,
+                              const std::vector<double>& c,
+                              const std::vector<double>& d,
+                              std::vector<double>* solutionVector);
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/spline/SplineParameterizer.h b/wpilibc/src/main/native/include/frc/spline/SplineParameterizer.h
new file mode 100644
index 0000000..d3a5e6e
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/spline/SplineParameterizer.h
@@ -0,0 +1,142 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019-2020 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/*
+ * MIT License
+ *
+ * Copyright (c) 2018 Team 254
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ */
+
+#pragma once
+
+#include <frc/spline/Spline.h>
+
+#include <stack>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include <units/units.h>
+#include <wpi/Twine.h>
+
+namespace frc {
+
+/**
+ * Class used to parameterize a spline by its arc length.
+ */
+class SplineParameterizer {
+ public:
+  using PoseWithCurvature = std::pair<Pose2d, curvature_t>;
+
+  struct MalformedSplineException : public std::runtime_error {
+    explicit MalformedSplineException(const char* what_arg)
+        : runtime_error(what_arg) {}
+  };
+
+  /**
+   * Parameterizes the spline. This method breaks up the spline into various
+   * arcs until their dx, dy, and dtheta are within specific tolerances.
+   *
+   * @param spline The spline to parameterize.
+   * @param t0 Starting internal spline parameter. It is recommended to leave
+   * this as default.
+   * @param t1 Ending internal spline parameter. It is recommended to leave this
+   * as default.
+   *
+   * @return A vector of poses and curvatures that represents various points on
+   * the spline.
+   */
+  template <int Dim>
+  static std::vector<PoseWithCurvature> Parameterize(const Spline<Dim>& spline,
+                                                     double t0 = 0.0,
+                                                     double t1 = 1.0) {
+    std::vector<PoseWithCurvature> splinePoints;
+
+    // The parameterization does not add the initial point. Let's add that.
+    splinePoints.push_back(spline.GetPoint(t0));
+
+    // We use an "explicit stack" to simulate recursion, instead of a recursive
+    // function call This give us greater control, instead of a stack overflow
+    std::stack<StackContents> stack;
+    stack.emplace(StackContents{t0, t1});
+
+    StackContents current;
+    PoseWithCurvature start;
+    PoseWithCurvature end;
+    int iterations = 0;
+
+    while (!stack.empty()) {
+      current = stack.top();
+      stack.pop();
+      start = spline.GetPoint(current.t0);
+      end = spline.GetPoint(current.t1);
+
+      const auto twist = start.first.Log(end.first);
+
+      if (units::math::abs(twist.dy) > kMaxDy ||
+          units::math::abs(twist.dx) > kMaxDx ||
+          units::math::abs(twist.dtheta) > kMaxDtheta) {
+        stack.emplace(StackContents{(current.t0 + current.t1) / 2, current.t1});
+        stack.emplace(StackContents{current.t0, (current.t0 + current.t1) / 2});
+      } else {
+        splinePoints.push_back(spline.GetPoint(current.t1));
+      }
+
+      if (iterations++ >= kMaxIterations) {
+        throw MalformedSplineException(
+            "Could not parameterize a malformed spline. "
+            "This means that you probably had two or more adjacent "
+            "waypoints that were very close together with headings "
+            "in opposing directions.");
+      }
+    }
+
+    return splinePoints;
+  }
+
+ private:
+  // Constraints for spline parameterization.
+  static constexpr units::meter_t kMaxDx = 5_in;
+  static constexpr units::meter_t kMaxDy = 0.05_in;
+  static constexpr units::radian_t kMaxDtheta = 0.0872_rad;
+
+  struct StackContents {
+    double t0;
+    double t1;
+  };
+
+  /**
+   * A malformed spline does not actually explode the LIFO stack size. Instead,
+   * the stack size stays at a relatively small number (e.g. 30) and never
+   * decreases. Because of this, we must count iterations. Even long, complex
+   * paths don't usually go over 300 iterations, so hitting this maximum should
+   * definitely indicate something has gone wrong.
+   */
+  static constexpr int kMaxIterations = 5000;
+
+  friend class CubicHermiteSplineTest;
+  friend class QuinticHermiteSplineTest;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/trajectory/Trajectory.h b/wpilibc/src/main/native/include/frc/trajectory/Trajectory.h
new file mode 100644
index 0000000..13e32d6
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/trajectory/Trajectory.h
@@ -0,0 +1,160 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <vector>
+
+#include <units/units.h>
+
+#include "frc/geometry/Pose2d.h"
+#include "frc/geometry/Transform2d.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace frc {
+
+/**
+ * Define a unit for curvature.
+ */
+using curvature_t = units::unit_t<
+    units::compound_unit<units::radian, units::inverse<units::meter>>>;
+
+/**
+ * Represents a time-parameterized trajectory. The trajectory contains of
+ * various States that represent the pose, curvature, time elapsed, velocity,
+ * and acceleration at that point.
+ */
+class Trajectory {
+ public:
+  /**
+   * Represents one point on the trajectory.
+   */
+  struct State {
+    // The time elapsed since the beginning of the trajectory.
+    units::second_t t = 0_s;
+
+    // The speed at that point of the trajectory.
+    units::meters_per_second_t velocity = 0_mps;
+
+    // The acceleration at that point of the trajectory.
+    units::meters_per_second_squared_t acceleration = 0_mps_sq;
+
+    // The pose at that point of the trajectory.
+    Pose2d pose;
+
+    // The curvature at that point of the trajectory.
+    curvature_t curvature{0.0};
+
+    /**
+     * Checks equality between this State and another object.
+     *
+     * @param other The other object.
+     * @return Whether the two objects are equal.
+     */
+    bool operator==(const State& other) const;
+
+    /**
+     * Checks inequality between this State and another object.
+     *
+     * @param other The other object.
+     * @return Whether the two objects are not equal.
+     */
+    bool operator!=(const State& other) const;
+
+    /**
+     * Interpolates between two States.
+     *
+     * @param endValue The end value for the interpolation.
+     * @param i The interpolant (fraction).
+     *
+     * @return The interpolated state.
+     */
+    State Interpolate(State endValue, double i) const;
+  };
+
+  Trajectory() = default;
+
+  /**
+   * Constructs a trajectory from a vector of states.
+   */
+  explicit Trajectory(const std::vector<State>& states);
+
+  /**
+   * Returns the overall duration of the trajectory.
+   * @return The duration of the trajectory.
+   */
+  units::second_t TotalTime() const { return m_totalTime; }
+
+  /**
+   * Return the states of the trajectory.
+   * @return The states of the trajectory.
+   */
+  const std::vector<State>& States() const { return m_states; }
+
+  /**
+   * Sample the trajectory at a point in time.
+   *
+   * @param t The point in time since the beginning of the trajectory to sample.
+   * @return The state at that point in time.
+   */
+  State Sample(units::second_t t) const;
+
+  /**
+   * Transforms all poses in the trajectory by the given transform. This is
+   * useful for converting a robot-relative trajectory into a field-relative
+   * trajectory. This works with respect to the first pose in the trajectory.
+   *
+   * @param transform The transform to transform the trajectory by.
+   * @return The transformed trajectory.
+   */
+  Trajectory TransformBy(const Transform2d& transform);
+
+  /**
+   * Transforms all poses in the trajectory so that they are relative to the
+   * given pose. This is useful for converting a field-relative trajectory
+   * into a robot-relative trajectory.
+   *
+   * @param pose The pose that is the origin of the coordinate frame that
+   *             the current trajectory will be transformed into.
+   * @return The transformed trajectory.
+   */
+  Trajectory RelativeTo(const Pose2d& pose);
+
+  /**
+   * Returns the initial pose of the trajectory.
+   *
+   * @return The initial pose of the trajectory.
+   */
+  Pose2d InitialPose() const { return Sample(0_s).pose; }
+
+ private:
+  std::vector<State> m_states;
+  units::second_t m_totalTime;
+
+  /**
+   * Linearly interpolates between two values.
+   *
+   * @param startValue The start value.
+   * @param endValue The end value.
+   * @param t The fraction for interpolation.
+   *
+   * @return The interpolated value.
+   */
+  template <typename T>
+  static T Lerp(const T& startValue, const T& endValue, const double t) {
+    return startValue + (endValue - startValue) * t;
+  }
+};
+
+void to_json(wpi::json& json, const Trajectory::State& state);
+
+void from_json(const wpi::json& json, Trajectory::State& state);
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/trajectory/TrajectoryConfig.h b/wpilibc/src/main/native/include/frc/trajectory/TrajectoryConfig.h
new file mode 100644
index 0000000..36118a0
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/trajectory/TrajectoryConfig.h
@@ -0,0 +1,165 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <utility>
+#include <vector>
+
+#include <units/units.h>
+
+#include "frc/kinematics/DifferentialDriveKinematics.h"
+#include "frc/kinematics/MecanumDriveKinematics.h"
+#include "frc/kinematics/SwerveDriveKinematics.h"
+#include "frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h"
+#include "frc/trajectory/constraint/MecanumDriveKinematicsConstraint.h"
+#include "frc/trajectory/constraint/SwerveDriveKinematicsConstraint.h"
+#include "frc/trajectory/constraint/TrajectoryConstraint.h"
+
+namespace frc {
+/**
+ * Represents the configuration for generating a trajectory. This class stores
+ * the start velocity, end velocity, max velocity, max acceleration, custom
+ * constraints, and the reversed flag.
+ *
+ * The class must be constructed with a max velocity and max acceleration.
+ * The other parameters (start velocity, end velocity, constraints, reversed)
+ * have been defaulted to reasonable values (0, 0, {}, false). These values can
+ * be changed via the SetXXX methods.
+ */
+class TrajectoryConfig {
+ public:
+  /**
+   * Constructs a config object.
+   * @param maxVelocity The max velocity of the trajectory.
+   * @param maxAcceleration The max acceleration of the trajectory.
+   */
+  TrajectoryConfig(units::meters_per_second_t maxVelocity,
+                   units::meters_per_second_squared_t maxAcceleration)
+      : m_maxVelocity(maxVelocity), m_maxAcceleration(maxAcceleration) {}
+
+  TrajectoryConfig(const TrajectoryConfig&) = delete;
+  TrajectoryConfig& operator=(const TrajectoryConfig&) = delete;
+
+  TrajectoryConfig(TrajectoryConfig&&) = default;
+  TrajectoryConfig& operator=(TrajectoryConfig&&) = default;
+
+  /**
+   * Sets the start velocity of the trajectory.
+   * @param startVelocity The start velocity of the trajectory.
+   */
+  void SetStartVelocity(units::meters_per_second_t startVelocity) {
+    m_startVelocity = startVelocity;
+  }
+
+  /**
+   * Sets the end velocity of the trajectory.
+   * @param endVelocity The end velocity of the trajectory.
+   */
+  void SetEndVelocity(units::meters_per_second_t endVelocity) {
+    m_endVelocity = endVelocity;
+  }
+
+  /**
+   * Sets the reversed flag of the trajectory.
+   * @param reversed Whether the trajectory should be reversed or not.
+   */
+  void SetReversed(bool reversed) { m_reversed = reversed; }
+
+  /**
+   * Adds a user-defined constraint to the trajectory.
+   * @param constraint The user-defined constraint.
+   */
+  template <typename Constraint, typename = std::enable_if_t<std::is_base_of_v<
+                                     TrajectoryConstraint, Constraint>>>
+  void AddConstraint(Constraint constraint) {
+    m_constraints.emplace_back(std::make_unique<Constraint>(constraint));
+  }
+
+  /**
+   * Adds a differential drive kinematics constraint to ensure that
+   * no wheel velocity of a differential drive goes above the max velocity.
+   *
+   * @param kinematics The differential drive kinematics.
+   */
+  void SetKinematics(const DifferentialDriveKinematics& kinematics) {
+    AddConstraint(
+        DifferentialDriveKinematicsConstraint(kinematics, m_maxVelocity));
+  }
+
+  /**
+   * Adds a mecanum drive kinematics constraint to ensure that
+   * no wheel velocity of a mecanum drive goes above the max velocity.
+   *
+   * @param kinematics The mecanum drive kinematics.
+   */
+  void SetKinematics(MecanumDriveKinematics kinematics) {
+    AddConstraint(MecanumDriveKinematicsConstraint(kinematics, m_maxVelocity));
+  }
+
+  /**
+   * Adds a swerve drive kinematics constraint to ensure that
+   * no wheel velocity of a swerve drive goes above the max velocity.
+   *
+   * @param kinematics The swerve drive kinematics.
+   */
+  template <size_t NumModules>
+  void SetKinematics(SwerveDriveKinematics<NumModules>& kinematics) {
+    AddConstraint(SwerveDriveKinematicsConstraint(kinematics, m_maxVelocity));
+  }
+
+  /**
+   * Returns the starting velocity of the trajectory.
+   * @return The starting velocity of the trajectory.
+   */
+  units::meters_per_second_t StartVelocity() const { return m_startVelocity; }
+
+  /**
+   * Returns the ending velocity of the trajectory.
+   * @return The ending velocity of the trajectory.
+   */
+  units::meters_per_second_t EndVelocity() const { return m_endVelocity; }
+
+  /**
+   * Returns the maximum velocity of the trajectory.
+   * @return The maximum velocity of the trajectory.
+   */
+  units::meters_per_second_t MaxVelocity() const { return m_maxVelocity; }
+
+  /**
+   * Returns the maximum acceleration of the trajectory.
+   * @return The maximum acceleration of the trajectory.
+   */
+  units::meters_per_second_squared_t MaxAcceleration() const {
+    return m_maxAcceleration;
+  }
+
+  /**
+   * Returns the user-defined constraints of the trajectory.
+   * @return The user-defined constraints of the trajectory.
+   */
+  const std::vector<std::unique_ptr<TrajectoryConstraint>>& Constraints()
+      const {
+    return m_constraints;
+  }
+
+  /**
+   * Returns whether the trajectory is reversed or not.
+   * @return whether the trajectory is reversed or not.
+   */
+  bool IsReversed() const { return m_reversed; }
+
+ private:
+  units::meters_per_second_t m_startVelocity = 0_mps;
+  units::meters_per_second_t m_endVelocity = 0_mps;
+  units::meters_per_second_t m_maxVelocity;
+  units::meters_per_second_squared_t m_maxAcceleration;
+  std::vector<std::unique_ptr<TrajectoryConstraint>> m_constraints;
+  bool m_reversed = false;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/trajectory/TrajectoryGenerator.h b/wpilibc/src/main/native/include/frc/trajectory/TrajectoryGenerator.h
new file mode 100644
index 0000000..40e7e7b
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/trajectory/TrajectoryGenerator.h
@@ -0,0 +1,120 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019-2020 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <utility>
+#include <vector>
+
+#include "frc/spline/SplineParameterizer.h"
+#include "frc/trajectory/Trajectory.h"
+#include "frc/trajectory/TrajectoryConfig.h"
+#include "frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h"
+#include "frc/trajectory/constraint/TrajectoryConstraint.h"
+
+namespace frc {
+/**
+ * Helper class used to generate trajectories with various constraints.
+ */
+class TrajectoryGenerator {
+ public:
+  using PoseWithCurvature = std::pair<Pose2d, curvature_t>;
+
+  /**
+   * Generates a trajectory from the given control vectors and config. This
+   * method uses clamped cubic splines -- a method in which the exterior control
+   * vectors and interior waypoints are provided. The headings are automatically
+   * determined at the interior points to ensure continuous curvature.
+   *
+   * @param initial           The initial control vector.
+   * @param interiorWaypoints The interior waypoints.
+   * @param end               The ending control vector.
+   * @param config            The configuration for the trajectory.
+   * @return The generated trajectory.
+   */
+  static Trajectory GenerateTrajectory(
+      Spline<3>::ControlVector initial,
+      const std::vector<Translation2d>& interiorWaypoints,
+      Spline<3>::ControlVector end, const TrajectoryConfig& config);
+
+  /**
+   * Generates a trajectory from the given waypoints and config. This method
+   * uses clamped cubic splines -- a method in which the initial pose, final
+   * pose, and interior waypoints are provided.  The headings are automatically
+   * determined at the interior points to ensure continuous curvature.
+   *
+   * @param start             The starting pose.
+   * @param interiorWaypoints The interior waypoints.
+   * @param end               The ending pose.
+   * @param config            The configuration for the trajectory.
+   * @return The generated trajectory.
+   */
+  static Trajectory GenerateTrajectory(
+      const Pose2d& start, const std::vector<Translation2d>& interiorWaypoints,
+      const Pose2d& end, const TrajectoryConfig& config);
+
+  /**
+   * Generates a trajectory from the given quintic control vectors and config.
+   * This method uses quintic hermite splines -- therefore, all points must be
+   * represented by control vectors. Continuous curvature is guaranteed in this
+   * method.
+   *
+   * @param controlVectors List of quintic control vectors.
+   * @param config         The configuration for the trajectory.
+   * @return The generated trajectory.
+   */
+  static Trajectory GenerateTrajectory(
+      std::vector<Spline<5>::ControlVector> controlVectors,
+      const TrajectoryConfig& config);
+
+  /**
+   * Generates a trajectory from the given waypoints and config. This method
+   * uses quintic hermite splines -- therefore, all points must be represented
+   * by Pose2d objects. Continuous curvature is guaranteed in this method.
+   *
+   * @param waypoints List of waypoints..
+   * @param config    The configuration for the trajectory.
+   * @return The generated trajectory.
+   */
+  static Trajectory GenerateTrajectory(const std::vector<Pose2d>& waypoints,
+                                       const TrajectoryConfig& config);
+
+  /**
+   * Generate spline points from a vector of splines by parameterizing the
+   * splines.
+   *
+   * @param splines The splines to parameterize.
+   *
+   * @return The spline points for use in time parameterization of a trajectory.
+   */
+  template <typename Spline>
+  static std::vector<PoseWithCurvature> SplinePointsFromSplines(
+      const std::vector<Spline>& splines) {
+    // Create the vector of spline points.
+    std::vector<PoseWithCurvature> splinePoints;
+
+    // Add the first point to the vector.
+    splinePoints.push_back(splines.front().GetPoint(0.0));
+
+    // Iterate through the vector and parameterize each spline, adding the
+    // parameterized points to the final vector.
+    for (auto&& spline : splines) {
+      auto points = SplineParameterizer::Parameterize(spline);
+      // Append the array of poses to the vector. We are removing the first
+      // point because it's a duplicate of the last point from the previous
+      // spline.
+      splinePoints.insert(std::end(splinePoints), std::begin(points) + 1,
+                          std::end(points));
+    }
+    return splinePoints;
+  }
+
+ private:
+  static const Trajectory kDoNothingTrajectory;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/trajectory/TrajectoryParameterizer.h b/wpilibc/src/main/native/include/frc/trajectory/TrajectoryParameterizer.h
new file mode 100644
index 0000000..b8ea8da
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/trajectory/TrajectoryParameterizer.h
@@ -0,0 +1,107 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/*
+ * MIT License
+ *
+ * Copyright (c) 2018 Team 254
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ */
+
+#pragma once
+
+#include <memory>
+#include <utility>
+#include <vector>
+
+#include "frc/trajectory/Trajectory.h"
+#include "frc/trajectory/constraint/TrajectoryConstraint.h"
+
+namespace frc {
+/**
+ * Class used to parameterize a trajectory by time.
+ */
+class TrajectoryParameterizer {
+ public:
+  using PoseWithCurvature = std::pair<Pose2d, curvature_t>;
+
+  /**
+   * Parameterize the trajectory by time. This is where the velocity profile is
+   * generated.
+   *
+   * The derivation of the algorithm used can be found here:
+   * <http://www2.informatik.uni-freiburg.de/~lau/students/Sprunk2008.pdf>
+   *
+   * @param points Reference to the spline points.
+   * @param constraints A vector of various velocity and acceleration
+   * constraints.
+   * @param startVelocity The start velocity for the trajectory.
+   * @param endVelocity The end velocity for the trajectory.
+   * @param maxVelocity The max velocity for the trajectory.
+   * @param maxAcceleration The max acceleration for the trajectory.
+   * @param reversed Whether the robot should move backwards. Note that the
+   * robot will still move from a -> b -> ... -> z as defined in the waypoints.
+   *
+   * @return The trajectory.
+   */
+  static Trajectory TimeParameterizeTrajectory(
+      const std::vector<PoseWithCurvature>& points,
+      const std::vector<std::unique_ptr<TrajectoryConstraint>>& constraints,
+      units::meters_per_second_t startVelocity,
+      units::meters_per_second_t endVelocity,
+      units::meters_per_second_t maxVelocity,
+      units::meters_per_second_squared_t maxAcceleration, bool reversed);
+
+ private:
+  constexpr static double kEpsilon = 1E-6;
+
+  /**
+   * Represents a constrained state that is used when time parameterizing a
+   * trajectory. Each state has the pose, curvature, distance from the start of
+   * the trajectory, max velocity, min acceleration and max acceleration.
+   */
+  struct ConstrainedState {
+    PoseWithCurvature pose = {Pose2d(), curvature_t(0.0)};
+    units::meter_t distance = 0_m;
+    units::meters_per_second_t maxVelocity = 0_mps;
+    units::meters_per_second_squared_t minAcceleration = 0_mps_sq;
+    units::meters_per_second_squared_t maxAcceleration = 0_mps_sq;
+  };
+
+  /**
+   * Enforces acceleration limits as defined by the constraints. This function
+   * is used when time parameterizing a trajectory.
+   *
+   * @param reverse Whether the robot is traveling backwards.
+   * @param constraints A vector of the user-defined velocity and acceleration
+   * constraints.
+   * @param state Pointer to the constrained state that we are operating on.
+   * This is mutated in place.
+   */
+  static void EnforceAccelerationLimits(
+      bool reverse,
+      const std::vector<std::unique_ptr<TrajectoryConstraint>>& constraints,
+      ConstrainedState* state);
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/trajectory/TrajectoryUtil.h b/wpilibc/src/main/native/include/frc/trajectory/TrajectoryUtil.h
new file mode 100644
index 0000000..700ed9c
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/trajectory/TrajectoryUtil.h
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+
+#include "frc/trajectory/Trajectory.h"
+
+namespace frc {
+class TrajectoryUtil {
+ public:
+  TrajectoryUtil() = delete;
+
+  /**
+   * Exports a Trajectory to a PathWeaver-style JSON file.
+   *
+   * @param trajectory the trajectory to export
+   * @param path the path of the file to export to
+   *
+   * @return The interpolated state.
+   */
+  static void ToPathweaverJson(const Trajectory& trajectory,
+                               const wpi::Twine& path);
+  /**
+   * Imports a Trajectory from a PathWeaver-style JSON file.
+   *
+   * @param path The path of the json file to import from.
+   *
+   * @return The trajectory represented by the file.
+   */
+  static Trajectory FromPathweaverJson(const wpi::Twine& path);
+
+  /**
+     * Deserializes a Trajectory from PathWeaver-style JSON.
+
+     * @param json the string containing the serialized JSON
+
+     * @return the trajectory represented by the JSON
+     */
+  static std::string SerializeTrajectory(const Trajectory& trajectory);
+
+  /**
+   * Serializes a Trajectory to PathWeaver-style JSON.
+
+   * @param trajectory the trajectory to export
+
+   * @return the string containing the serialized JSON
+   */
+  static Trajectory DeserializeTrajectory(wpi::StringRef json_str);
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/trajectory/TrapezoidProfile.h b/wpilibc/src/main/native/include/frc/trajectory/TrapezoidProfile.h
new file mode 100644
index 0000000..575088e
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/trajectory/TrapezoidProfile.h
@@ -0,0 +1,157 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared 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/FRCUsageReporting.h>
+#include <units/units.h>
+
+namespace frc {
+
+/**
+ * A trapezoid-shaped velocity profile.
+ *
+ * While this class can be used for a profiled movement from start to finish,
+ * the intended usage is to filter a reference's dynamics based on trapezoidal
+ * velocity constraints. To compute the reference obeying this constraint, do
+ * the following.
+ *
+ * Initialization:
+ * @code{.cpp}
+ * TrapezoidalMotionProfile::Constraints constraints{kMaxV, kMaxA};
+ * double previousProfiledReference = initialReference;
+ * @endcode
+ *
+ * Run on update:
+ * @code{.cpp}
+ * TrapezoidalMotionProfile profile{constraints, unprofiledReference,
+ *                                  previousProfiledReference};
+ * previousProfiledReference = profile.Calculate(timeSincePreviousUpdate);
+ * @endcode
+ *
+ * where `unprofiledReference` is free to change between calls. Note that when
+ * the unprofiled reference is within the constraints, `Calculate()` returns the
+ * unprofiled reference unchanged.
+ *
+ * Otherwise, a timer can be started to provide monotonic values for
+ * `Calculate()` and to determine when the profile has completed via
+ * `IsFinished()`.
+ */
+template <class Distance>
+class TrapezoidProfile {
+  using Distance_t = units::unit_t<Distance>;
+  using Velocity =
+      units::compound_unit<Distance, units::inverse<units::seconds>>;
+  using Velocity_t = units::unit_t<Velocity>;
+  using Acceleration =
+      units::compound_unit<Velocity, units::inverse<units::seconds>>;
+  using Acceleration_t = units::unit_t<Acceleration>;
+
+ public:
+  class Constraints {
+   public:
+    Constraints() {
+      HAL_Report(HALUsageReporting::kResourceType_TrapezoidProfile, 1);
+    }
+    Constraints(Velocity_t maxVelocity_, Acceleration_t maxAcceleration_)
+        : maxVelocity{maxVelocity_}, maxAcceleration{maxAcceleration_} {
+      HAL_Report(HALUsageReporting::kResourceType_TrapezoidProfile, 1);
+    }
+    Velocity_t maxVelocity{0};
+    Acceleration_t maxAcceleration{0};
+  };
+
+  class State {
+   public:
+    Distance_t position{0};
+    Velocity_t velocity{0};
+    bool operator==(const State& rhs) const {
+      return position == rhs.position && velocity == rhs.velocity;
+    }
+    bool operator!=(const State& rhs) const { return !(*this == rhs); }
+  };
+
+  /**
+   * Construct a TrapezoidProfile.
+   *
+   * @param constraints The constraints on the profile, like maximum velocity.
+   * @param goal        The desired state when the profile is complete.
+   * @param initial     The initial state (usually the current state).
+   */
+  TrapezoidProfile(Constraints constraints, State goal,
+                   State initial = State{Distance_t(0), Velocity_t(0)});
+
+  TrapezoidProfile(const TrapezoidProfile&) = default;
+  TrapezoidProfile& operator=(const TrapezoidProfile&) = default;
+  TrapezoidProfile(TrapezoidProfile&&) = default;
+  TrapezoidProfile& operator=(TrapezoidProfile&&) = default;
+
+  /**
+   * Calculate the correct position and velocity for the profile at a time t
+   * where the beginning of the profile was at time t = 0.
+   *
+   * @param t The time since the beginning of the profile.
+   */
+  State Calculate(units::second_t t) const;
+
+  /**
+   * Returns the time left until a target distance in the profile is reached.
+   *
+   * @param target The target distance.
+   */
+  units::second_t TimeLeftUntil(Distance_t target) const;
+
+  /**
+   * Returns the total time the profile takes to reach the goal.
+   */
+  units::second_t TotalTime() const { return m_endDeccel; }
+
+  /**
+   * Returns true if the profile has reached the goal.
+   *
+   * The profile has reached the goal if the time since the profile started
+   * has exceeded the profile's total time.
+   *
+   * @param t The time since the beginning of the profile.
+   */
+  bool IsFinished(units::second_t t) const { return t >= TotalTime(); }
+
+ private:
+  /**
+   * Returns true if the profile inverted.
+   *
+   * The profile is inverted if goal position is less than the initial position.
+   *
+   * @param initial The initial state (usually the current state).
+   * @param goal    The desired state when the profile is complete.
+   */
+  static bool ShouldFlipAcceleration(const State& initial, const State& goal) {
+    return initial.position > goal.position;
+  }
+
+  // Flip the sign of the velocity and position if the profile is inverted
+  State Direct(const State& in) const {
+    State result = in;
+    result.position *= m_direction;
+    result.velocity *= m_direction;
+    return result;
+  }
+
+  // The direction of the profile, either 1 for forwards or -1 for inverted
+  int m_direction;
+
+  Constraints m_constraints;
+  State m_initial;
+  State m_goal;
+
+  units::second_t m_endAccel;
+  units::second_t m_endFullSpeed;
+  units::second_t m_endDeccel;
+};
+}  // namespace frc
+
+#include "TrapezoidProfile.inc"
diff --git a/wpilibc/src/main/native/include/frc/trajectory/TrapezoidProfile.inc b/wpilibc/src/main/native/include/frc/trajectory/TrapezoidProfile.inc
new file mode 100644
index 0000000..50f232d
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/trajectory/TrapezoidProfile.inc
@@ -0,0 +1,163 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared 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 Distance>
+TrapezoidProfile<Distance>::TrapezoidProfile(Constraints constraints,
+                                             State goal, State initial)
+    : m_direction{ShouldFlipAcceleration(initial, goal) ? -1 : 1},
+      m_constraints(constraints),
+      m_initial(Direct(initial)),
+      m_goal(Direct(goal)) {
+  if (m_initial.velocity > m_constraints.maxVelocity) {
+    m_initial.velocity = m_constraints.maxVelocity;
+  }
+
+  // Deal with a possibly truncated motion profile (with nonzero initial or
+  // final velocity) by calculating the parameters as if the profile began and
+  // ended at zero velocity
+  units::second_t cutoffBegin =
+      m_initial.velocity / m_constraints.maxAcceleration;
+  Distance_t cutoffDistBegin =
+      cutoffBegin * cutoffBegin * m_constraints.maxAcceleration / 2.0;
+
+  units::second_t cutoffEnd = m_goal.velocity / m_constraints.maxAcceleration;
+  Distance_t cutoffDistEnd =
+      cutoffEnd * cutoffEnd * m_constraints.maxAcceleration / 2.0;
+
+  // Now we can calculate the parameters as if it was a full trapezoid instead
+  // of a truncated one
+
+  Distance_t fullTrapezoidDist =
+      cutoffDistBegin + (m_goal.position - m_initial.position) + cutoffDistEnd;
+  units::second_t accelerationTime =
+      m_constraints.maxVelocity / m_constraints.maxAcceleration;
+
+  Distance_t fullSpeedDist =
+      fullTrapezoidDist -
+      accelerationTime * accelerationTime * m_constraints.maxAcceleration;
+
+  // Handle the case where the profile never reaches full speed
+  if (fullSpeedDist < Distance_t(0)) {
+    accelerationTime =
+        units::math::sqrt(fullTrapezoidDist / m_constraints.maxAcceleration);
+    fullSpeedDist = Distance_t(0);
+  }
+
+  m_endAccel = accelerationTime - cutoffBegin;
+  m_endFullSpeed = m_endAccel + fullSpeedDist / m_constraints.maxVelocity;
+  m_endDeccel = m_endFullSpeed + accelerationTime - cutoffEnd;
+}
+
+template <class Distance>
+typename TrapezoidProfile<Distance>::State
+TrapezoidProfile<Distance>::Calculate(units::second_t t) const {
+  State result = m_initial;
+
+  if (t < m_endAccel) {
+    result.velocity += t * m_constraints.maxAcceleration;
+    result.position +=
+        (m_initial.velocity + t * m_constraints.maxAcceleration / 2.0) * t;
+  } else if (t < m_endFullSpeed) {
+    result.velocity = m_constraints.maxVelocity;
+    result.position += (m_initial.velocity +
+                        m_endAccel * m_constraints.maxAcceleration / 2.0) *
+                           m_endAccel +
+                       m_constraints.maxVelocity * (t - m_endAccel);
+  } else if (t <= m_endDeccel) {
+    result.velocity =
+        m_goal.velocity + (m_endDeccel - t) * m_constraints.maxAcceleration;
+    units::second_t timeLeft = m_endDeccel - t;
+    result.position =
+        m_goal.position -
+        (m_goal.velocity + timeLeft * m_constraints.maxAcceleration / 2.0) *
+            timeLeft;
+  } else {
+    result = m_goal;
+  }
+
+  return Direct(result);
+}
+
+template <class Distance>
+units::second_t TrapezoidProfile<Distance>::TimeLeftUntil(
+    Distance_t target) const {
+  Distance_t position = m_initial.position * m_direction;
+  Velocity_t velocity = m_initial.velocity * m_direction;
+
+  units::second_t endAccel = m_endAccel * m_direction;
+  units::second_t endFullSpeed = m_endFullSpeed * m_direction - endAccel;
+
+  if (target < position) {
+    endAccel *= -1.0;
+    endFullSpeed *= -1.0;
+    velocity *= -1.0;
+  }
+
+  endAccel = units::math::max(endAccel, 0_s);
+  endFullSpeed = units::math::max(endFullSpeed, 0_s);
+  units::second_t endDeccel = m_endDeccel - endAccel - endFullSpeed;
+  endDeccel = units::math::max(endDeccel, 0_s);
+
+  const Acceleration_t acceleration = m_constraints.maxAcceleration;
+  const Acceleration_t decceleration = -m_constraints.maxAcceleration;
+
+  Distance_t distToTarget = units::math::abs(target - position);
+
+  if (distToTarget < Distance_t(1e-6)) {
+    return 0_s;
+  }
+
+  Distance_t accelDist =
+      velocity * endAccel + 0.5 * acceleration * endAccel * endAccel;
+
+  Velocity_t deccelVelocity;
+  if (endAccel > 0_s) {
+    deccelVelocity = units::math::sqrt(
+        units::math::abs(velocity * velocity + 2 * acceleration * accelDist));
+  } else {
+    deccelVelocity = velocity;
+  }
+
+  Distance_t deccelDist =
+      deccelVelocity * endDeccel + 0.5 * decceleration * endDeccel * endDeccel;
+
+  deccelDist = units::math::max(deccelDist, Distance_t(0));
+
+  Distance_t fullSpeedDist = m_constraints.maxVelocity * endFullSpeed;
+
+  if (accelDist > distToTarget) {
+    accelDist = distToTarget;
+    fullSpeedDist = Distance_t(0);
+    deccelDist = Distance_t(0);
+  } else if (accelDist + fullSpeedDist > distToTarget) {
+    fullSpeedDist = distToTarget - accelDist;
+    deccelDist = Distance_t(0);
+  } else {
+    deccelDist = distToTarget - fullSpeedDist - accelDist;
+  }
+
+  units::second_t accelTime =
+      (-velocity + units::math::sqrt(units::math::abs(
+                       velocity * velocity + 2 * acceleration * accelDist))) /
+      acceleration;
+
+  units::second_t deccelTime =
+      (-deccelVelocity +
+       units::math::sqrt(units::math::abs(deccelVelocity * deccelVelocity +
+                                          2 * decceleration * deccelDist))) /
+      decceleration;
+
+  units::second_t fullSpeedTime = fullSpeedDist / m_constraints.maxVelocity;
+
+  return accelTime + fullSpeedTime + deccelTime;
+}
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/trajectory/constraint/CentripetalAccelerationConstraint.h b/wpilibc/src/main/native/include/frc/trajectory/constraint/CentripetalAccelerationConstraint.h
new file mode 100644
index 0000000..de25738
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/trajectory/constraint/CentripetalAccelerationConstraint.h
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+
+#include "frc/trajectory/constraint/TrajectoryConstraint.h"
+
+namespace frc {
+
+/**
+ * A constraint on the maximum absolute centripetal acceleration allowed when
+ * traversing a trajectory. The centripetal acceleration of a robot is defined
+ * as the velocity squared divided by the radius of curvature.
+ *
+ * Effectively, limiting the maximum centripetal acceleration will cause the
+ * robot to slow down around tight turns, making it easier to track trajectories
+ * with sharp turns.
+ */
+class CentripetalAccelerationConstraint : public TrajectoryConstraint {
+ public:
+  explicit CentripetalAccelerationConstraint(
+      units::meters_per_second_squared_t maxCentripetalAcceleration);
+
+  units::meters_per_second_t MaxVelocity(
+      const Pose2d& pose, curvature_t curvature,
+      units::meters_per_second_t velocity) override;
+
+  MinMax MinMaxAcceleration(const Pose2d& pose, curvature_t curvature,
+                            units::meters_per_second_t speed) override;
+
+ private:
+  units::meters_per_second_squared_t m_maxCentripetalAcceleration;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h b/wpilibc/src/main/native/include/frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h
new file mode 100644
index 0000000..6259c96
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+
+#include "frc/kinematics/DifferentialDriveKinematics.h"
+#include "frc/trajectory/constraint/TrajectoryConstraint.h"
+
+/**
+ * A class that enforces constraints on the differential drive kinematics.
+ * This can be used to ensure that the trajectory is constructed so that the
+ * commanded velocities for both sides of the drivetrain stay below a certain
+ * limit.
+ */
+namespace frc {
+class DifferentialDriveKinematicsConstraint : public TrajectoryConstraint {
+ public:
+  DifferentialDriveKinematicsConstraint(DifferentialDriveKinematics kinematics,
+                                        units::meters_per_second_t maxSpeed);
+
+  units::meters_per_second_t MaxVelocity(
+      const Pose2d& pose, curvature_t curvature,
+      units::meters_per_second_t velocity) override;
+
+  MinMax MinMaxAcceleration(const Pose2d& pose, curvature_t curvature,
+                            units::meters_per_second_t speed) override;
+
+ private:
+  DifferentialDriveKinematics m_kinematics;
+  units::meters_per_second_t m_maxSpeed;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/trajectory/constraint/DifferentialDriveVoltageConstraint.h b/wpilibc/src/main/native/include/frc/trajectory/constraint/DifferentialDriveVoltageConstraint.h
new file mode 100644
index 0000000..50ace85
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/trajectory/constraint/DifferentialDriveVoltageConstraint.h
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+
+#include "frc/controller/SimpleMotorFeedforward.h"
+#include "frc/kinematics/DifferentialDriveKinematics.h"
+#include "frc/trajectory/constraint/TrajectoryConstraint.h"
+
+namespace frc {
+/**
+ * A class that enforces constraints on differential drive voltage expenditure
+ * based on the motor dynamics and the drive kinematics.  Ensures that the
+ * acceleration of any wheel of the robot while following the trajectory is
+ * never higher than what can be achieved with the given maximum voltage.
+ */
+class DifferentialDriveVoltageConstraint : public TrajectoryConstraint {
+ public:
+  /**
+   * Creates a new DifferentialDriveVoltageConstraint.
+   *
+   * @param feedforward A feedforward component describing the behavior of the
+   * drive.
+   * @param kinematics  A kinematics component describing the drive geometry.
+   * @param maxVoltage  The maximum voltage available to the motors while
+   * following the path. Should be somewhat less than the nominal battery
+   * voltage (12V) to account for "voltage sag" due to current draw.
+   */
+  DifferentialDriveVoltageConstraint(
+      SimpleMotorFeedforward<units::meter> feedforward,
+      DifferentialDriveKinematics kinematics, units::volt_t maxVoltage);
+
+  units::meters_per_second_t MaxVelocity(
+      const Pose2d& pose, curvature_t curvature,
+      units::meters_per_second_t velocity) override;
+
+  MinMax MinMaxAcceleration(const Pose2d& pose, curvature_t curvature,
+                            units::meters_per_second_t speed) override;
+
+ private:
+  SimpleMotorFeedforward<units::meter> m_feedforward;
+  DifferentialDriveKinematics m_kinematics;
+  units::volt_t m_maxVoltage;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/trajectory/constraint/MecanumDriveKinematicsConstraint.h b/wpilibc/src/main/native/include/frc/trajectory/constraint/MecanumDriveKinematicsConstraint.h
new file mode 100644
index 0000000..53e3953
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/trajectory/constraint/MecanumDriveKinematicsConstraint.h
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <cmath>
+
+#include <units/units.h>
+
+#include "frc/kinematics/MecanumDriveKinematics.h"
+#include "frc/trajectory/constraint/TrajectoryConstraint.h"
+
+/**
+ * A class that enforces constraints on the differential drive kinematics.
+ * This can be used to ensure that the trajectory is constructed so that the
+ * commanded velocities for both sides of the drivetrain stay below a certain
+ * limit.
+ */
+namespace frc {
+class MecanumDriveKinematicsConstraint : public TrajectoryConstraint {
+ public:
+  MecanumDriveKinematicsConstraint(MecanumDriveKinematics kinematics,
+                                   units::meters_per_second_t maxSpeed);
+
+  units::meters_per_second_t MaxVelocity(
+      const Pose2d& pose, curvature_t curvature,
+      units::meters_per_second_t velocity) override;
+
+  MinMax MinMaxAcceleration(const Pose2d& pose, curvature_t curvature,
+                            units::meters_per_second_t speed) override;
+
+ private:
+  MecanumDriveKinematics m_kinematics;
+  units::meters_per_second_t m_maxSpeed;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/trajectory/constraint/SwerveDriveKinematicsConstraint.h b/wpilibc/src/main/native/include/frc/trajectory/constraint/SwerveDriveKinematicsConstraint.h
new file mode 100644
index 0000000..a8ad870
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/trajectory/constraint/SwerveDriveKinematicsConstraint.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <cmath>
+
+#include <units/units.h>
+
+#include "frc/kinematics/SwerveDriveKinematics.h"
+#include "frc/trajectory/constraint/TrajectoryConstraint.h"
+
+/**
+ * A class that enforces constraints on the differential drive kinematics.
+ * This can be used to ensure that the trajectory is constructed so that the
+ * commanded velocities for both sides of the drivetrain stay below a certain
+ * limit.
+ */
+namespace frc {
+
+template <size_t NumModules>
+class SwerveDriveKinematicsConstraint : public TrajectoryConstraint {
+ public:
+  SwerveDriveKinematicsConstraint(
+      frc::SwerveDriveKinematics<NumModules> kinematics,
+      units::meters_per_second_t maxSpeed);
+
+  units::meters_per_second_t MaxVelocity(
+      const Pose2d& pose, curvature_t curvature,
+      units::meters_per_second_t velocity) override;
+
+  MinMax MinMaxAcceleration(const Pose2d& pose, curvature_t curvature,
+                            units::meters_per_second_t speed) override;
+
+ private:
+  frc::SwerveDriveKinematics<NumModules> m_kinematics;
+  units::meters_per_second_t m_maxSpeed;
+};
+}  // namespace frc
+
+#include "SwerveDriveKinematicsConstraint.inc"
diff --git a/wpilibc/src/main/native/include/frc/trajectory/constraint/SwerveDriveKinematicsConstraint.inc b/wpilibc/src/main/native/include/frc/trajectory/constraint/SwerveDriveKinematicsConstraint.inc
new file mode 100644
index 0000000..c3437d5
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/trajectory/constraint/SwerveDriveKinematicsConstraint.inc
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/**
+ * A class that enforces constraints on the differential drive kinematics.
+ * This can be used to ensure that the trajectory is constructed so that the
+ * commanded velocities for both sides of the drivetrain stay below a certain
+ * limit.
+ */
+
+namespace frc {
+
+template <size_t NumModules>
+SwerveDriveKinematicsConstraint<NumModules>::SwerveDriveKinematicsConstraint(
+    frc::SwerveDriveKinematics<NumModules> kinematics,
+    units::meters_per_second_t maxSpeed)
+    : m_kinematics(kinematics), m_maxSpeed(maxSpeed) {}
+
+template <size_t NumModules>
+units::meters_per_second_t
+SwerveDriveKinematicsConstraint<NumModules>::MaxVelocity(
+    const Pose2d& pose, curvature_t curvature,
+    units::meters_per_second_t velocity) {
+  auto xVelocity = velocity * pose.Rotation().Cos();
+  auto yVelocity = velocity * pose.Rotation().Sin();
+  auto wheelSpeeds = m_kinematics.ToSwerveModuleStates(
+      {xVelocity, yVelocity, velocity * curvature});
+  m_kinematics.NormalizeWheelSpeeds(&wheelSpeeds, m_maxSpeed);
+
+  auto normSpeeds = m_kinematics.ToChassisSpeeds(wheelSpeeds);
+
+  return units::math::hypot(normSpeeds.vx, normSpeeds.vy);
+}
+
+template <size_t NumModules>
+TrajectoryConstraint::MinMax
+SwerveDriveKinematicsConstraint<NumModules>::MinMaxAcceleration(
+    const Pose2d& pose, curvature_t curvature,
+    units::meters_per_second_t speed) {
+  return {};
+}
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/trajectory/constraint/TrajectoryConstraint.h b/wpilibc/src/main/native/include/frc/trajectory/constraint/TrajectoryConstraint.h
new file mode 100644
index 0000000..dcde8c4
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/trajectory/constraint/TrajectoryConstraint.h
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <limits>
+
+#include <units/units.h>
+
+#include "frc/geometry/Pose2d.h"
+#include "frc/spline/Spline.h"
+
+namespace frc {
+/**
+ * An interface for defining user-defined velocity and acceleration constraints
+ * while generating trajectories.
+ */
+class TrajectoryConstraint {
+ public:
+  TrajectoryConstraint() = default;
+
+  TrajectoryConstraint(const TrajectoryConstraint&) = default;
+  TrajectoryConstraint& operator=(const TrajectoryConstraint&) = default;
+
+  TrajectoryConstraint(TrajectoryConstraint&&) = default;
+  TrajectoryConstraint& operator=(TrajectoryConstraint&&) = default;
+
+  virtual ~TrajectoryConstraint() = default;
+
+  /**
+   * Represents a minimum and maximum acceleration.
+   */
+  struct MinMax {
+    /**
+     * The minimum acceleration.
+     */
+    units::meters_per_second_squared_t minAcceleration{
+        -std::numeric_limits<double>::max()};
+
+    /**
+     * The maximum acceleration.
+     */
+    units::meters_per_second_squared_t maxAcceleration{
+        std::numeric_limits<double>::max()};
+  };
+
+  /**
+   * Returns the max velocity given the current pose and curvature.
+   *
+   * @param pose The pose at the current point in the trajectory.
+   * @param curvature The curvature at the current point in the trajectory.
+   * @param velocity The velocity at the current point in the trajectory before
+   *                                constraints are applied.
+   *
+   * @return The absolute maximum velocity.
+   */
+  virtual units::meters_per_second_t MaxVelocity(
+      const Pose2d& pose, curvature_t curvature,
+      units::meters_per_second_t velocity) = 0;
+
+  /**
+   * Returns the minimum and maximum allowable acceleration for the trajectory
+   * given pose, curvature, and speed.
+   *
+   * @param pose The pose at the current point in the trajectory.
+   * @param curvature The curvature at the current point in the trajectory.
+   * @param speed The speed at the current point in the trajectory.
+   *
+   * @return The min and max acceleration bounds.
+   */
+  virtual MinMax MinMaxAcceleration(const Pose2d& pose, curvature_t curvature,
+                                    units::meters_per_second_t speed) = 0;
+};
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/util/Color.h b/wpilibc/src/main/native/include/frc/util/Color.h
new file mode 100644
index 0000000..2538d60
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/util/Color.h
@@ -0,0 +1,949 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared 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 {
+
+/**
+ * Represents colors that can be used with Addressable LEDs.
+ *
+ * Limited to 12 bits of precision.
+ */
+class Color {
+ public:
+  /*
+   * FIRST Colors
+   */
+
+  /**
+   * #1560BD.
+   */
+  static const Color kDenim;
+
+  /**
+   * #0066B3.
+   */
+  static const Color kFirstBlue;
+
+  /**
+   * #ED1C24.
+   */
+  static const Color kFirstRed;
+
+  /*
+   * Standard Colors
+   */
+
+  /**
+   * #F0F8FF.
+   */
+  static const Color kAliceBlue;
+
+  /**
+   * #FAEBD7.
+   */
+  static const Color kAntiqueWhite;
+
+  /**
+   * #00FFFF.
+   */
+  static const Color kAqua;
+
+  /**
+   * #7FFFD4.
+   */
+  static const Color kAquamarine;
+
+  /**
+   * #F0FFFF.
+   */
+  static const Color kAzure;
+
+  /**
+   * #F5F5DC.
+   */
+  static const Color kBeige;
+
+  /**
+   * #FFE4C4.
+   */
+  static const Color kBisque;
+
+  /**
+   * #000000.
+   */
+  static const Color kBlack;
+
+  /**
+   * #FFEBCD.
+   */
+  static const Color kBlanchedAlmond;
+
+  /**
+   * #0000FF.
+   */
+  static const Color kBlue;
+
+  /**
+   * #8A2BE2.
+   */
+  static const Color kBlueViolet;
+
+  /**
+   * #A52A2A.
+   */
+  static const Color kBrown;
+
+  /**
+   * #DEB887.
+   */
+  static const Color kBurlywood;
+
+  /**
+   * #5F9EA0.
+   */
+  static const Color kCadetBlue;
+
+  /**
+   * #7FFF00.
+   */
+  static const Color kChartreuse;
+
+  /**
+   * #D2691E.
+   */
+  static const Color kChocolate;
+
+  /**
+   * #FF7F50.
+   */
+  static const Color kCoral;
+
+  /**
+   * #6495ED.
+   */
+  static const Color kCornflowerBlue;
+
+  /**
+   * #FFF8DC.
+   */
+  static const Color kCornsilk;
+
+  /**
+   * #DC143C.
+   */
+  static const Color kCrimson;
+
+  /**
+   * #00FFFF.
+   */
+  static const Color kCyan;
+
+  /**
+   * #00008B.
+   */
+  static const Color kDarkBlue;
+
+  /**
+   * #008B8B.
+   */
+  static const Color kDarkCyan;
+
+  /**
+   * #B8860B.
+   */
+  static const Color kDarkGoldenrod;
+
+  /**
+   * #A9A9A9.
+   */
+  static const Color kDarkGray;
+
+  /**
+   * #006400.
+   */
+  static const Color kDarkGreen;
+
+  /**
+   * #BDB76B.
+   */
+  static const Color kDarkKhaki;
+
+  /**
+   * #8B008B.
+   */
+  static const Color kDarkMagenta;
+
+  /**
+   * #556B2F.
+   */
+  static const Color kDarkOliveGreen;
+
+  /**
+   * #FF8C00.
+   */
+  static const Color kDarkOrange;
+
+  /**
+   * #9932CC.
+   */
+  static const Color kDarkOrchid;
+
+  /**
+   * #8B0000.
+   */
+  static const Color kDarkRed;
+
+  /**
+   * #E9967A.
+   */
+  static const Color kDarkSalmon;
+
+  /**
+   * #8FBC8F.
+   */
+  static const Color kDarkSeaGreen;
+
+  /**
+   * #483D8B.
+   */
+  static const Color kDarkSlateBlue;
+
+  /**
+   * #2F4F4F.
+   */
+  static const Color kDarkSlateGray;
+
+  /**
+   * #00CED1.
+   */
+  static const Color kDarkTurquoise;
+
+  /**
+   * #9400D3.
+   */
+  static const Color kDarkViolet;
+
+  /**
+   * #FF1493.
+   */
+  static const Color kDeepPink;
+
+  /**
+   * #00BFFF.
+   */
+  static const Color kDeepSkyBlue;
+
+  /**
+   * #696969.
+   */
+  static const Color kDimGray;
+
+  /**
+   * #1E90FF.
+   */
+  static const Color kDodgerBlue;
+
+  /**
+   * #B22222.
+   */
+  static const Color kFirebrick;
+
+  /**
+   * #FFFAF0.
+   */
+  static const Color kFloralWhite;
+
+  /**
+   * #228B22.
+   */
+  static const Color kForestGreen;
+
+  /**
+   * #FF00FF.
+   */
+  static const Color kFuchsia;
+
+  /**
+   * #DCDCDC.
+   */
+  static const Color kGainsboro;
+
+  /**
+   * #F8F8FF.
+   */
+  static const Color kGhostWhite;
+
+  /**
+   * #FFD700.
+   */
+  static const Color kGold;
+
+  /**
+   * #DAA520.
+   */
+  static const Color kGoldenrod;
+
+  /**
+   * #808080.
+   */
+  static const Color kGray;
+
+  /**
+   * #008000.
+   */
+  static const Color kGreen;
+
+  /**
+   * #ADFF2F.
+   */
+  static const Color kGreenYellow;
+
+  /**
+   * #F0FFF0.
+   */
+  static const Color kHoneydew;
+
+  /**
+   * #FF69B4.
+   */
+  static const Color kHotPink;
+
+  /**
+   * #CD5C5C.
+   */
+  static const Color kIndianRed;
+
+  /**
+   * #4B0082.
+   */
+  static const Color kIndigo;
+
+  /**
+   * #FFFFF0.
+   */
+  static const Color kIvory;
+
+  /**
+   * #F0E68C.
+   */
+  static const Color kKhaki;
+
+  /**
+   * #E6E6FA.
+   */
+  static const Color kLavender;
+
+  /**
+   * #FFF0F5.
+   */
+  static const Color kLavenderBlush;
+
+  /**
+   * #7CFC00.
+   */
+  static const Color kLawnGreen;
+
+  /**
+   * #FFFACD.
+   */
+  static const Color kLemonChiffon;
+
+  /**
+   * #ADD8E6.
+   */
+  static const Color kLightBlue;
+
+  /**
+   * #F08080.
+   */
+  static const Color kLightCoral;
+
+  /**
+   * #E0FFFF.
+   */
+  static const Color kLightCyan;
+
+  /**
+   * #FAFAD2.
+   */
+  static const Color kLightGoldenrodYellow;
+
+  /**
+   * #D3D3D3.
+   */
+  static const Color kLightGray;
+
+  /**
+   * #90EE90.
+   */
+  static const Color kLightGreen;
+
+  /**
+   * #FFB6C1.
+   */
+  static const Color kLightPink;
+
+  /**
+   * #FFA07A.
+   */
+  static const Color kLightSalmon;
+
+  /**
+   * #20B2AA.
+   */
+  static const Color kLightSeagGeen;
+
+  /**
+   * #87CEFA.
+   */
+  static const Color kLightSkyBlue;
+
+  /**
+   * #778899.
+   */
+  static const Color kLightSlateGray;
+
+  /**
+   * #B0C4DE.
+   */
+  static const Color kLightSteellue;
+
+  /**
+   * #FFFFE0.
+   */
+  static const Color kLightYellow;
+
+  /**
+   * #00FF00.
+   */
+  static const Color kLime;
+
+  /**
+   * #32CD32.
+   */
+  static const Color kLimeGreen;
+
+  /**
+   * #FAF0E6.
+   */
+  static const Color kLinen;
+
+  /**
+   * #FF00FF.
+   */
+  static const Color kMagenta;
+
+  /**
+   * #800000.
+   */
+  static const Color kMaroon;
+
+  /**
+   * #66CDAA.
+   */
+  static const Color kMediumAquamarine;
+
+  /**
+   * #0000CD.
+   */
+  static const Color kMediumBlue;
+
+  /**
+   * #BA55D3.
+   */
+  static const Color kMediumOrchid;
+
+  /**
+   * #9370DB.
+   */
+  static const Color kMediumPurple;
+
+  /**
+   * #3CB371.
+   */
+  static const Color kMediumSeaGreen;
+
+  /**
+   * #7B68EE.
+   */
+  static const Color kMediumSlateBlue;
+
+  /**
+   * #00FA9A.
+   */
+  static const Color kMediumSpringGreen;
+
+  /**
+   * #48D1CC.
+   */
+  static const Color kMediumTurquoise;
+
+  /**
+   * #C71585.
+   */
+  static const Color kMediumVioletRed;
+
+  /**
+   * #191970.
+   */
+  static const Color kMidnightBlue;
+
+  /**
+   * #F5FFFA.
+   */
+  static const Color kMintcream;
+
+  /**
+   * #FFE4E1.
+   */
+  static const Color kMistyRose;
+
+  /**
+   * #FFE4B5.
+   */
+  static const Color kMoccasin;
+
+  /**
+   * #FFDEAD.
+   */
+  static const Color kNavajoWhite;
+
+  /**
+   * #000080.
+   */
+  static const Color kNavy;
+
+  /**
+   * #FDF5E6.
+   */
+  static const Color kOldLace;
+
+  /**
+   * #808000.
+   */
+  static const Color kOlive;
+
+  /**
+   * #6B8E23.
+   */
+  static const Color kOliveDrab;
+
+  /**
+   * #FFA500.
+   */
+  static const Color kOrange;
+
+  /**
+   * #FF4500.
+   */
+  static const Color kOrangeRed;
+
+  /**
+   * #DA70D6.
+   */
+  static const Color kOrchid;
+
+  /**
+   * #EEE8AA.
+   */
+  static const Color kPaleGoldenrod;
+
+  /**
+   * #98FB98.
+   */
+  static const Color kPaleGreen;
+
+  /**
+   * #AFEEEE.
+   */
+  static const Color kPaleTurquoise;
+
+  /**
+   * #DB7093.
+   */
+  static const Color kPaleVioletRed;
+
+  /**
+   * #FFEFD5.
+   */
+  static const Color kPapayaWhip;
+
+  /**
+   * #FFDAB9.
+   */
+  static const Color kPeachPuff;
+
+  /**
+   * #CD853F.
+   */
+  static const Color kPeru;
+
+  /**
+   * #FFC0CB.
+   */
+  static const Color kPink;
+
+  /**
+   * #DDA0DD.
+   */
+  static const Color kPlum;
+
+  /**
+   * #B0E0E6.
+   */
+  static const Color kPowderBlue;
+
+  /**
+   * #800080.
+   */
+  static const Color kPurple;
+
+  /**
+   * #FF0000.
+   */
+  static const Color kRed;
+
+  /**
+   * #BC8F8F.
+   */
+  static const Color kRosyBrown;
+
+  /**
+   * #4169E1.
+   */
+  static const Color kRoyalBlue;
+
+  /**
+   * #8B4513.
+   */
+  static const Color kSaddleBrown;
+
+  /**
+   * #FA8072.
+   */
+  static const Color kSalmon;
+
+  /**
+   * #F4A460.
+   */
+  static const Color kSandyBrown;
+
+  /**
+   * #2E8B57.
+   */
+  static const Color kSeaGreen;
+
+  /**
+   * #FFF5EE.
+   */
+  static const Color kSeashell;
+
+  /**
+   * #A0522D.
+   */
+  static const Color kSienna;
+
+  /**
+   * #C0C0C0.
+   */
+  static const Color kSilver;
+
+  /**
+   * #87CEEB.
+   */
+  static const Color kSkyBlue;
+
+  /**
+   * #6A5ACD.
+   */
+  static const Color kSlateBlue;
+
+  /**
+   * #708090.
+   */
+  static const Color kSlateGray;
+
+  /**
+   * #FFFAFA.
+   */
+  static const Color kSnow;
+
+  /**
+   * #00FF7F.
+   */
+  static const Color kSpringGreen;
+
+  /**
+   * #4682B4.
+   */
+  static const Color kSteelBlue;
+
+  /**
+   * #D2B48C.
+   */
+  static const Color kTan;
+
+  /**
+   * #008080.
+   */
+  static const Color kTeal;
+
+  /**
+   * #D8BFD8.
+   */
+  static const Color kThistle;
+
+  /**
+   * #FF6347.
+   */
+  static const Color kTomato;
+
+  /**
+   * #40E0D0.
+   */
+  static const Color kTurquoise;
+
+  /**
+   * #EE82EE.
+   */
+  static const Color kViolet;
+
+  /**
+   * #F5DEB3.
+   */
+  static const Color kWheat;
+
+  /**
+   * #FFFFFF.
+   */
+  static const Color kWhite;
+
+  /**
+   * #F5F5F5.
+   */
+  static const Color kWhiteSmoke;
+
+  /**
+   * #FFFF00.
+   */
+  static const Color kYellow;
+
+  /**
+   * #9ACD32.
+   */
+  static const Color kYellowGreen;
+
+  constexpr Color() = default;
+
+  /**
+   * Constructs a Color.
+   *
+   * @param red Red value (0-1)
+   * @param green Green value (0-1)
+   * @param blue Blue value (0-1)
+   */
+  constexpr Color(double r, double g, double b)
+      : red(roundAndClamp(r)),
+        green(roundAndClamp(g)),
+        blue(roundAndClamp(b)) {}
+
+  double red = 0.0;
+  double green = 0.0;
+  double blue = 0.0;
+
+ private:
+  static constexpr double kPrecision = 1.0 / (1 << 12);
+
+  static constexpr double roundAndClamp(double value) {
+    const auto rounded =
+        (static_cast<int>(value / kPrecision) + 0.5) * kPrecision;
+    return std::clamp(rounded, 0.0, 1.0);
+  }
+};
+
+inline bool operator==(const Color& c1, const Color& c2) {
+  return c1.red == c2.red && c1.green == c2.green && c1.blue == c2.blue;
+}
+
+/*
+ * FIRST Colors
+ */
+inline constexpr Color Color::kDenim{0.0823529412, 0.376470589, 0.7411764706};
+inline constexpr Color Color::kFirstBlue{0.0, 0.4, 0.7019607844};
+inline constexpr Color Color::kFirstRed{0.9294117648, 0.1098039216,
+                                        0.1411764706};
+
+/*
+ * Standard Colors
+ */
+inline constexpr Color Color::kAliceBlue{0.9411765f, 0.972549f, 1.0f};
+inline constexpr Color Color::kAntiqueWhite{0.98039216f, 0.92156863f,
+                                            0.84313726f};
+inline constexpr Color Color::kAqua{0.0f, 1.0f, 1.0f};
+inline constexpr Color Color::kAquamarine{0.49803922f, 1.0f, 0.83137256f};
+inline constexpr Color Color::kAzure{0.9411765f, 1.0f, 1.0f};
+inline constexpr Color Color::kBeige{0.9607843f, 0.9607843f, 0.8627451f};
+inline constexpr Color Color::kBisque{1.0f, 0.89411765f, 0.76862746f};
+inline constexpr Color Color::kBlack{0.0f, 0.0f, 0.0f};
+inline constexpr Color Color::kBlanchedAlmond{1.0f, 0.92156863f, 0.8039216f};
+inline constexpr Color Color::kBlue{0.0f, 0.0f, 1.0f};
+inline constexpr Color Color::kBlueViolet{0.5411765f, 0.16862746f, 0.8862745f};
+inline constexpr Color Color::kBrown{0.64705884f, 0.16470589f, 0.16470589f};
+inline constexpr Color Color::kBurlywood{0.87058824f, 0.72156864f, 0.5294118f};
+inline constexpr Color Color::kCadetBlue{0.37254903f, 0.61960787f, 0.627451f};
+inline constexpr Color Color::kChartreuse{0.49803922f, 1.0f, 0.0f};
+inline constexpr Color Color::kChocolate{0.8235294f, 0.4117647f, 0.11764706f};
+inline constexpr Color Color::kCoral{1.0f, 0.49803922f, 0.3137255f};
+inline constexpr Color Color::kCornflowerBlue{0.39215687f, 0.58431375f,
+                                              0.92941177f};
+inline constexpr Color Color::kCornsilk{1.0f, 0.972549f, 0.8627451f};
+inline constexpr Color Color::kCrimson{0.8627451f, 0.078431375f, 0.23529412f};
+inline constexpr Color Color::kCyan{0.0f, 1.0f, 1.0f};
+inline constexpr Color Color::kDarkBlue{0.0f, 0.0f, 0.54509807f};
+inline constexpr Color Color::kDarkCyan{0.0f, 0.54509807f, 0.54509807f};
+inline constexpr Color Color::kDarkGoldenrod{0.72156864f, 0.5254902f,
+                                             0.043137256f};
+inline constexpr Color Color::kDarkGray{0.6627451f, 0.6627451f, 0.6627451f};
+inline constexpr Color Color::kDarkGreen{0.0f, 0.39215687f, 0.0f};
+inline constexpr Color Color::kDarkKhaki{0.7411765f, 0.7176471f, 0.41960785f};
+inline constexpr Color Color::kDarkMagenta{0.54509807f, 0.0f, 0.54509807f};
+inline constexpr Color Color::kDarkOliveGreen{0.33333334f, 0.41960785f,
+                                              0.18431373f};
+inline constexpr Color Color::kDarkOrange{1.0f, 0.54901963f, 0.0f};
+inline constexpr Color Color::kDarkOrchid{0.6f, 0.19607843f, 0.8f};
+inline constexpr Color Color::kDarkRed{0.54509807f, 0.0f, 0.0f};
+inline constexpr Color Color::kDarkSalmon{0.9137255f, 0.5882353f, 0.47843137f};
+inline constexpr Color Color::kDarkSeaGreen{0.56078434f, 0.7372549f,
+                                            0.56078434f};
+inline constexpr Color Color::kDarkSlateBlue{0.28235295f, 0.23921569f,
+                                             0.54509807f};
+inline constexpr Color Color::kDarkSlateGray{0.18431373f, 0.30980393f,
+                                             0.30980393f};
+inline constexpr Color Color::kDarkTurquoise{0.0f, 0.80784315f, 0.81960785f};
+inline constexpr Color Color::kDarkViolet{0.5803922f, 0.0f, 0.827451f};
+inline constexpr Color Color::kDeepPink{1.0f, 0.078431375f, 0.5764706f};
+inline constexpr Color Color::kDeepSkyBlue{0.0f, 0.7490196f, 1.0f};
+inline constexpr Color Color::kDimGray{0.4117647f, 0.4117647f, 0.4117647f};
+inline constexpr Color Color::kDodgerBlue{0.11764706f, 0.5647059f, 1.0f};
+inline constexpr Color Color::kFirebrick{0.69803923f, 0.13333334f, 0.13333334f};
+inline constexpr Color Color::kFloralWhite{1.0f, 0.98039216f, 0.9411765f};
+inline constexpr Color Color::kForestGreen{0.13333334f, 0.54509807f,
+                                           0.13333334f};
+inline constexpr Color Color::kFuchsia{1.0f, 0.0f, 1.0f};
+inline constexpr Color Color::kGainsboro{0.8627451f, 0.8627451f, 0.8627451f};
+inline constexpr Color Color::kGhostWhite{0.972549f, 0.972549f, 1.0f};
+inline constexpr Color Color::kGold{1.0f, 0.84313726f, 0.0f};
+inline constexpr Color Color::kGoldenrod{0.85490197f, 0.64705884f, 0.1254902f};
+inline constexpr Color Color::kGray{0.5019608f, 0.5019608f, 0.5019608f};
+inline constexpr Color Color::kGreen{0.0f, 0.5019608f, 0.0f};
+inline constexpr Color Color::kGreenYellow{0.6784314f, 1.0f, 0.18431373f};
+inline constexpr Color Color::kHoneydew{0.9411765f, 1.0f, 0.9411765f};
+inline constexpr Color Color::kHotPink{1.0f, 0.4117647f, 0.7058824f};
+inline constexpr Color Color::kIndianRed{0.8039216f, 0.36078432f, 0.36078432f};
+inline constexpr Color Color::kIndigo{0.29411766f, 0.0f, 0.50980395f};
+inline constexpr Color Color::kIvory{1.0f, 1.0f, 0.9411765f};
+inline constexpr Color Color::kKhaki{0.9411765f, 0.9019608f, 0.54901963f};
+inline constexpr Color Color::kLavender{0.9019608f, 0.9019608f, 0.98039216f};
+inline constexpr Color Color::kLavenderBlush{1.0f, 0.9411765f, 0.9607843f};
+inline constexpr Color Color::kLawnGreen{0.4862745f, 0.9882353f, 0.0f};
+inline constexpr Color Color::kLemonChiffon{1.0f, 0.98039216f, 0.8039216f};
+inline constexpr Color Color::kLightBlue{0.6784314f, 0.84705883f, 0.9019608f};
+inline constexpr Color Color::kLightCoral{0.9411765f, 0.5019608f, 0.5019608f};
+inline constexpr Color Color::kLightCyan{0.8784314f, 1.0f, 1.0f};
+inline constexpr Color Color::kLightGoldenrodYellow{0.98039216f, 0.98039216f,
+                                                    0.8235294f};
+inline constexpr Color Color::kLightGray{0.827451f, 0.827451f, 0.827451f};
+inline constexpr Color Color::kLightGreen{0.5647059f, 0.93333334f, 0.5647059f};
+inline constexpr Color Color::kLightPink{1.0f, 0.7137255f, 0.75686276f};
+inline constexpr Color Color::kLightSalmon{1.0f, 0.627451f, 0.47843137f};
+inline constexpr Color Color::kLightSeagGeen{0.1254902f, 0.69803923f,
+                                             0.6666667f};
+inline constexpr Color Color::kLightSkyBlue{0.5294118f, 0.80784315f,
+                                            0.98039216f};
+inline constexpr Color Color::kLightSlateGray{0.46666667f, 0.53333336f, 0.6f};
+inline constexpr Color Color::kLightSteellue{0.6901961f, 0.76862746f,
+                                             0.87058824f};
+inline constexpr Color Color::kLightYellow{1.0f, 1.0f, 0.8784314f};
+inline constexpr Color Color::kLime{0.0f, 1.0f, 0.0f};
+inline constexpr Color Color::kLimeGreen{0.19607843f, 0.8039216f, 0.19607843f};
+inline constexpr Color Color::kLinen{0.98039216f, 0.9411765f, 0.9019608f};
+inline constexpr Color Color::kMagenta{1.0f, 0.0f, 1.0f};
+inline constexpr Color Color::kMaroon{0.5019608f, 0.0f, 0.0f};
+inline constexpr Color Color::kMediumAquamarine{0.4f, 0.8039216f, 0.6666667f};
+inline constexpr Color Color::kMediumBlue{0.0f, 0.0f, 0.8039216f};
+inline constexpr Color Color::kMediumOrchid{0.7294118f, 0.33333334f, 0.827451f};
+inline constexpr Color Color::kMediumPurple{0.5764706f, 0.4392157f,
+                                            0.85882354f};
+inline constexpr Color Color::kMediumSeaGreen{0.23529412f, 0.7019608f,
+                                              0.44313726f};
+inline constexpr Color Color::kMediumSlateBlue{0.48235294f, 0.40784314f,
+                                               0.93333334f};
+inline constexpr Color Color::kMediumSpringGreen{0.0f, 0.98039216f, 0.6039216f};
+inline constexpr Color Color::kMediumTurquoise{0.28235295f, 0.81960785f, 0.8f};
+inline constexpr Color Color::kMediumVioletRed{0.78039217f, 0.08235294f,
+                                               0.52156866f};
+inline constexpr Color Color::kMidnightBlue{0.09803922f, 0.09803922f,
+                                            0.4392157f};
+inline constexpr Color Color::kMintcream{0.9607843f, 1.0f, 0.98039216f};
+inline constexpr Color Color::kMistyRose{1.0f, 0.89411765f, 0.88235295f};
+inline constexpr Color Color::kMoccasin{1.0f, 0.89411765f, 0.70980394f};
+inline constexpr Color Color::kNavajoWhite{1.0f, 0.87058824f, 0.6784314f};
+inline constexpr Color Color::kNavy{0.0f, 0.0f, 0.5019608f};
+inline constexpr Color Color::kOldLace{0.99215686f, 0.9607843f, 0.9019608f};
+inline constexpr Color Color::kOlive{0.5019608f, 0.5019608f, 0.0f};
+inline constexpr Color Color::kOliveDrab{0.41960785f, 0.5568628f, 0.13725491f};
+inline constexpr Color Color::kOrange{1.0f, 0.64705884f, 0.0f};
+inline constexpr Color Color::kOrangeRed{1.0f, 0.27058825f, 0.0f};
+inline constexpr Color Color::kOrchid{0.85490197f, 0.4392157f, 0.8392157f};
+inline constexpr Color Color::kPaleGoldenrod{0.93333334f, 0.9098039f,
+                                             0.6666667f};
+inline constexpr Color Color::kPaleGreen{0.59607846f, 0.9843137f, 0.59607846f};
+inline constexpr Color Color::kPaleTurquoise{0.6862745f, 0.93333334f,
+                                             0.93333334f};
+inline constexpr Color Color::kPaleVioletRed{0.85882354f, 0.4392157f,
+                                             0.5764706f};
+inline constexpr Color Color::kPapayaWhip{1.0f, 0.9372549f, 0.8352941f};
+inline constexpr Color Color::kPeachPuff{1.0f, 0.85490197f, 0.7254902f};
+inline constexpr Color Color::kPeru{0.8039216f, 0.52156866f, 0.24705882f};
+inline constexpr Color Color::kPink{1.0f, 0.7529412f, 0.79607844f};
+inline constexpr Color Color::kPlum{0.8666667f, 0.627451f, 0.8666667f};
+inline constexpr Color Color::kPowderBlue{0.6901961f, 0.8784314f, 0.9019608f};
+inline constexpr Color Color::kPurple{0.5019608f, 0.0f, 0.5019608f};
+inline constexpr Color Color::kRed{1.0f, 0.0f, 0.0f};
+inline constexpr Color Color::kRosyBrown{0.7372549f, 0.56078434f, 0.56078434f};
+inline constexpr Color Color::kRoyalBlue{0.25490198f, 0.4117647f, 0.88235295f};
+inline constexpr Color Color::kSaddleBrown{0.54509807f, 0.27058825f,
+                                           0.07450981f};
+inline constexpr Color Color::kSalmon{0.98039216f, 0.5019608f, 0.44705883f};
+inline constexpr Color Color::kSandyBrown{0.95686275f, 0.6431373f, 0.3764706f};
+inline constexpr Color Color::kSeaGreen{0.18039216f, 0.54509807f, 0.34117648f};
+inline constexpr Color Color::kSeashell{1.0f, 0.9607843f, 0.93333334f};
+inline constexpr Color Color::kSienna{0.627451f, 0.32156864f, 0.1764706f};
+inline constexpr Color Color::kSilver{0.7529412f, 0.7529412f, 0.7529412f};
+inline constexpr Color Color::kSkyBlue{0.5294118f, 0.80784315f, 0.92156863f};
+inline constexpr Color Color::kSlateBlue{0.41568628f, 0.3529412f, 0.8039216f};
+inline constexpr Color Color::kSlateGray{0.4392157f, 0.5019608f, 0.5647059f};
+inline constexpr Color Color::kSnow{1.0f, 0.98039216f, 0.98039216f};
+inline constexpr Color Color::kSpringGreen{0.0f, 1.0f, 0.49803922f};
+inline constexpr Color Color::kSteelBlue{0.27450982f, 0.50980395f, 0.7058824f};
+inline constexpr Color Color::kTan{0.8235294f, 0.7058824f, 0.54901963f};
+inline constexpr Color Color::kTeal{0.0f, 0.5019608f, 0.5019608f};
+inline constexpr Color Color::kThistle{0.84705883f, 0.7490196f, 0.84705883f};
+inline constexpr Color Color::kTomato{1.0f, 0.3882353f, 0.2784314f};
+inline constexpr Color Color::kTurquoise{0.2509804f, 0.8784314f, 0.8156863f};
+inline constexpr Color Color::kViolet{0.93333334f, 0.50980395f, 0.93333334f};
+inline constexpr Color Color::kWheat{0.9607843f, 0.87058824f, 0.7019608f};
+inline constexpr Color Color::kWhite{1.0f, 1.0f, 1.0f};
+inline constexpr Color Color::kWhiteSmoke{0.9607843f, 0.9607843f, 0.9607843f};
+inline constexpr Color Color::kYellow{1.0f, 1.0f, 0.0f};
+inline constexpr Color Color::kYellowGreen{0.6039216f, 0.8039216f, 0.19607843f};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/util/Color8Bit.h b/wpilibc/src/main/native/include/frc/util/Color8Bit.h
new file mode 100644
index 0000000..d5dba07
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/util/Color8Bit.h
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared 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 "Color.h"
+
+namespace frc {
+
+/**
+ * Represents colors that can be used with Addressable LEDs.
+ */
+class Color8Bit {
+ public:
+  constexpr Color8Bit() = default;
+
+  /**
+   * Constructs a Color8Bit.
+   *
+   * @param red Red value (0-255)
+   * @param green Green value (0-255)
+   * @param blue Blue value (0-255)
+   */
+  constexpr Color8Bit(int r, int g, int b)
+      : red(std::clamp(r, 0, 255)),
+        green(std::clamp(g, 0, 255)),
+        blue(std::clamp(b, 0, 255)) {}
+
+  /**
+   * Constructs a Color8Bit from a Color.
+   *
+   * @param color The color
+   */
+  constexpr Color8Bit(const Color& color)
+      : red(color.red * 255),
+        green(color.green * 255),
+        blue(color.blue * 255) {}
+
+  constexpr operator Color() const {
+    return Color(red / 255.0, green / 255.0, blue / 255.0);
+  }
+
+  int red = 0;
+  int green = 0;
+  int blue = 0;
+};
+
+inline bool operator==(const Color8Bit& c1, const Color8Bit& c2) {
+  return c1.red == c2.red && c1.green == c2.green && c1.blue == c2.blue;
+}
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc2/Timer.h b/wpilibc/src/main/native/include/frc2/Timer.h
new file mode 100644
index 0000000..c1eeb16
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc2/Timer.h
@@ -0,0 +1,138 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <units/units.h>
+#include <wpi/deprecated.h>
+#include <wpi/mutex.h>
+
+#include "frc/Base.h"
+
+namespace frc2 {
+
+/**
+ * Pause the task for a specified time.
+ *
+ * Pause the execution of the program for a specified period of time given in
+ * seconds. Motors will continue to run at their last assigned values, and
+ * sensors will continue to update. Only the task containing the wait will pause
+ * until the wait time is expired.
+ *
+ * @param seconds Length of time to pause, in seconds.
+ */
+void Wait(units::second_t seconds);
+
+/**
+ * @brief  Gives real-time clock system time with nanosecond resolution
+ * @return The time, just in case you want the robot to start autonomous at 8pm
+ *         on Saturday.
+ */
+units::second_t GetTime();
+
+/**
+ * A wrapper for the frc::Timer class that returns unit-typed values.
+ */
+class Timer {
+ public:
+  /**
+   * Create a new timer object.
+   *
+   * Create a new timer object and reset the time to zero. The timer is
+   * initially not running and must be started.
+   */
+  Timer();
+
+  virtual ~Timer() = default;
+
+  Timer(const Timer& rhs);
+  Timer& operator=(const Timer& rhs);
+  Timer(Timer&& rhs);
+  Timer& operator=(Timer&& rhs);
+
+  /**
+   * Get the current time from the timer. If the clock is running it is derived
+   * from the current system clock the start time stored in the timer class. If
+   * the clock is not running, then return the time when it was last stopped.
+   *
+   * @return Current time value for this timer in seconds
+   */
+  units::second_t Get() const;
+
+  /**
+   * Reset the timer by setting the time to 0.
+   *
+   * Make the timer startTime the current time so new requests will be relative
+   * to now.
+   */
+  void Reset();
+
+  /**
+   * Start the timer running.
+   *
+   * Just set the running flag to true indicating that all time requests should
+   * be relative to the system clock.
+   */
+  void Start();
+
+  /**
+   * Stop the timer.
+   *
+   * This computes the time as of now and clears the running flag, causing all
+   * subsequent time requests to be read from the accumulated time rather than
+   * looking at the system clock.
+   */
+  void Stop();
+
+  /**
+   * Check if the period specified has passed and if it has, advance the start
+   * time by that period. This is useful to decide if it's time to do periodic
+   * work without drifting later by the time it took to get around to checking.
+   *
+   * @param period The period to check for.
+   * @return       True if the period has passed.
+   */
+  bool HasPeriodPassed(units::second_t period);
+
+  /**
+   * Return the FPGA system clock time in seconds.
+   *
+   * Return the time from the FPGA hardware clock in seconds since the FPGA
+   * started. Rolls over after 71 minutes.
+   *
+   * @returns Robot running time in seconds.
+   */
+  static units::second_t GetFPGATimestamp();
+
+  /**
+   * Return the approximate match time.
+   *
+   * The FMS does not send an official match time to the robots, but does send
+   * an approximate match time. The value will count down the time remaining in
+   * the current period (auto or teleop).
+   *
+   * Warning: This is not an official time (so it cannot be used to dispute ref
+   * calls or guarantee that a function will trigger before the match ends).
+   *
+   * The Practice Match function of the DS approximates the behavior seen on the
+   * field.
+   *
+   * @return Time remaining in current match period (auto or teleop)
+   */
+  static units::second_t GetMatchTime();
+
+  // The time, in seconds, at which the 32-bit FPGA timestamp rolls over to 0
+  static const units::second_t kRolloverTime;
+
+ private:
+  units::second_t m_startTime = 0_s;
+  units::second_t m_accumulatedTime = 0_s;
+  bool m_running = false;
+  mutable wpi::mutex m_mutex;
+};
+
+}  // namespace frc2
diff --git a/wpilibc/src/test/native/c/test.c b/wpilibc/src/test/native/c/test.c
new file mode 100644
index 0000000..105e289
--- /dev/null
+++ b/wpilibc/src/test/native/c/test.c
@@ -0,0 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <cscore.h>
+#include <hal/HAL.h>
+#include <ntcore.h>
diff --git a/wpilibc/src/test/native/cpp/LinearFilterNoiseTest.cpp b/wpilibc/src/test/native/cpp/LinearFilterNoiseTest.cpp
new file mode 100644
index 0000000..0bb1002
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/LinearFilterNoiseTest.cpp
@@ -0,0 +1,94 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/LinearFilter.h"  // NOLINT(build/include_order)
+
+#include <cmath>
+#include <memory>
+#include <random>
+
+#include <units/units.h>
+#include <wpi/math>
+
+#include "gtest/gtest.h"
+
+// Filter constants
+static constexpr units::second_t kFilterStep = 0.005_s;
+static constexpr units::second_t kFilterTime = 2.0_s;
+static constexpr double kSinglePoleIIRTimeConstant = 0.015915;
+static constexpr int32_t kMovAvgTaps = 6;
+
+enum LinearFilterNoiseTestType { TEST_SINGLE_POLE_IIR, TEST_MOVAVG };
+
+std::ostream& operator<<(std::ostream& os,
+                         const LinearFilterNoiseTestType& type) {
+  switch (type) {
+    case TEST_SINGLE_POLE_IIR:
+      os << "LinearFilter SinglePoleIIR";
+      break;
+    case TEST_MOVAVG:
+      os << "LinearFilter MovingAverage";
+      break;
+  }
+
+  return os;
+}
+
+static double GetData(double t) {
+  return 100.0 * std::sin(2.0 * wpi::math::pi * t);
+}
+
+class LinearFilterNoiseTest
+    : public testing::TestWithParam<LinearFilterNoiseTestType> {
+ protected:
+  std::unique_ptr<frc::LinearFilter<double>> m_filter;
+
+  void SetUp() override {
+    switch (GetParam()) {
+      case TEST_SINGLE_POLE_IIR: {
+        m_filter = std::make_unique<frc::LinearFilter<double>>(
+            frc::LinearFilter<double>::SinglePoleIIR(kSinglePoleIIRTimeConstant,
+                                                     kFilterStep));
+        break;
+      }
+
+      case TEST_MOVAVG: {
+        m_filter = std::make_unique<frc::LinearFilter<double>>(
+            frc::LinearFilter<double>::MovingAverage(kMovAvgTaps));
+        break;
+      }
+    }
+  }
+};
+
+/**
+ * Test if the filter reduces the noise produced by a signal generator
+ */
+TEST_P(LinearFilterNoiseTest, NoiseReduce) {
+  double noiseGenError = 0.0;
+  double filterError = 0.0;
+
+  std::random_device rd;
+  std::mt19937 gen{rd()};
+  std::normal_distribution<double> distr{0.0, 10.0};
+
+  for (auto t = 0_s; t < kFilterTime; t += kFilterStep) {
+    double theory = GetData(t.to<double>());
+    double noise = distr(gen);
+    filterError += std::abs(m_filter->Calculate(theory + noise) - theory);
+    noiseGenError += std::abs(noise - theory);
+  }
+
+  RecordProperty("FilterError", filterError);
+
+  // The filter should have produced values closer to the theory
+  EXPECT_GT(noiseGenError, filterError)
+      << "Filter should have reduced noise accumulation but failed";
+}
+
+INSTANTIATE_TEST_SUITE_P(Test, LinearFilterNoiseTest,
+                         testing::Values(TEST_SINGLE_POLE_IIR, TEST_MOVAVG));
diff --git a/wpilibc/src/test/native/cpp/LinearFilterOutputTest.cpp b/wpilibc/src/test/native/cpp/LinearFilterOutputTest.cpp
new file mode 100644
index 0000000..8db91b3
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/LinearFilterOutputTest.cpp
@@ -0,0 +1,136 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/LinearFilter.h"  // NOLINT(build/include_order)
+
+#include <cmath>
+#include <functional>
+#include <memory>
+#include <random>
+
+#include <units/units.h>
+#include <wpi/math>
+
+#include "gtest/gtest.h"
+
+// Filter constants
+static constexpr units::second_t kFilterStep = 0.005_s;
+static constexpr units::second_t kFilterTime = 2.0_s;
+static constexpr double kSinglePoleIIRTimeConstant = 0.015915;
+static constexpr double kSinglePoleIIRExpectedOutput = -3.2172003;
+static constexpr double kHighPassTimeConstant = 0.006631;
+static constexpr double kHighPassExpectedOutput = 10.074717;
+static constexpr int32_t kMovAvgTaps = 6;
+static constexpr double kMovAvgExpectedOutput = -10.191644;
+
+enum LinearFilterOutputTestType {
+  TEST_SINGLE_POLE_IIR,
+  TEST_HIGH_PASS,
+  TEST_MOVAVG,
+  TEST_PULSE
+};
+
+std::ostream& operator<<(std::ostream& os,
+                         const LinearFilterOutputTestType& type) {
+  switch (type) {
+    case TEST_SINGLE_POLE_IIR:
+      os << "LinearFilter SinglePoleIIR";
+      break;
+    case TEST_HIGH_PASS:
+      os << "LinearFilter HighPass";
+      break;
+    case TEST_MOVAVG:
+      os << "LinearFilter MovingAverage";
+      break;
+    case TEST_PULSE:
+      os << "LinearFilter Pulse";
+      break;
+  }
+
+  return os;
+}
+
+static double GetData(double t) {
+  return 100.0 * std::sin(2.0 * wpi::math::pi * t) +
+         20.0 * std::cos(50.0 * wpi::math::pi * t);
+}
+
+static double GetPulseData(double t) {
+  if (std::abs(t - 1.0) < 0.001) {
+    return 1.0;
+  } else {
+    return 0.0;
+  }
+}
+
+/**
+ * A fixture that includes a consistent data source wrapped in a filter
+ */
+class LinearFilterOutputTest
+    : public testing::TestWithParam<LinearFilterOutputTestType> {
+ protected:
+  std::unique_ptr<frc::LinearFilter<double>> m_filter;
+  std::function<double(double)> m_data;
+  double m_expectedOutput = 0.0;
+
+  void SetUp() override {
+    switch (GetParam()) {
+      case TEST_SINGLE_POLE_IIR: {
+        m_filter = std::make_unique<frc::LinearFilter<double>>(
+            frc::LinearFilter<double>::SinglePoleIIR(kSinglePoleIIRTimeConstant,
+                                                     kFilterStep));
+        m_data = GetData;
+        m_expectedOutput = kSinglePoleIIRExpectedOutput;
+        break;
+      }
+
+      case TEST_HIGH_PASS: {
+        m_filter = std::make_unique<frc::LinearFilter<double>>(
+            frc::LinearFilter<double>::HighPass(kHighPassTimeConstant,
+                                                kFilterStep));
+        m_data = GetData;
+        m_expectedOutput = kHighPassExpectedOutput;
+        break;
+      }
+
+      case TEST_MOVAVG: {
+        m_filter = std::make_unique<frc::LinearFilter<double>>(
+            frc::LinearFilter<double>::MovingAverage(kMovAvgTaps));
+        m_data = GetData;
+        m_expectedOutput = kMovAvgExpectedOutput;
+        break;
+      }
+
+      case TEST_PULSE: {
+        m_filter = std::make_unique<frc::LinearFilter<double>>(
+            frc::LinearFilter<double>::MovingAverage(kMovAvgTaps));
+        m_data = GetPulseData;
+        m_expectedOutput = 0.0;
+        break;
+      }
+    }
+  }
+};
+
+/**
+ * Test if the linear filters produce consistent output for a given data set.
+ */
+TEST_P(LinearFilterOutputTest, Output) {
+  double filterOutput = 0.0;
+  for (auto t = 0_s; t < kFilterTime; t += kFilterStep) {
+    filterOutput = m_filter->Calculate(m_data(t.to<double>()));
+  }
+
+  RecordProperty("LinearFilterOutput", filterOutput);
+
+  EXPECT_FLOAT_EQ(m_expectedOutput, filterOutput)
+      << "Filter output didn't match expected value";
+}
+
+INSTANTIATE_TEST_SUITE_P(Test, LinearFilterOutputTest,
+                         testing::Values(TEST_SINGLE_POLE_IIR, TEST_HIGH_PASS,
+                                         TEST_MOVAVG, TEST_PULSE));
diff --git a/wpilibc/src/test/native/cpp/MedianFilterTest.cpp b/wpilibc/src/test/native/cpp/MedianFilterTest.cpp
new file mode 100644
index 0000000..7fe7d2e
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/MedianFilterTest.cpp
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/MedianFilter.h"
+#include "gtest/gtest.h"
+
+TEST(MedianFilterTest, MedianFilterNotFullTestEven) {
+  frc::MedianFilter<double> filter{10};
+
+  filter.Calculate(3);
+  filter.Calculate(0);
+  filter.Calculate(4);
+
+  EXPECT_EQ(filter.Calculate(1000), 3.5);
+}
+
+TEST(MedianFilterTest, MedianFilterNotFullTestOdd) {
+  frc::MedianFilter<double> filter{10};
+
+  filter.Calculate(3);
+  filter.Calculate(0);
+  filter.Calculate(4);
+  filter.Calculate(7);
+
+  EXPECT_EQ(filter.Calculate(1000), 4);
+}
+
+TEST(MedianFilterTest, MedianFilterFullTestEven) {
+  frc::MedianFilter<double> filter{6};
+
+  filter.Calculate(3);
+  filter.Calculate(0);
+  filter.Calculate(0);
+  filter.Calculate(5);
+  filter.Calculate(4);
+  filter.Calculate(1000);
+
+  EXPECT_EQ(filter.Calculate(99), 4.5);
+}
+
+TEST(MedianFilterTest, MedianFilterFullTestOdd) {
+  frc::MedianFilter<double> filter{5};
+
+  filter.Calculate(3);
+  filter.Calculate(0);
+  filter.Calculate(5);
+  filter.Calculate(4);
+  filter.Calculate(1000);
+
+  EXPECT_EQ(filter.Calculate(99), 5);
+}
diff --git a/wpilibc/src/test/native/cpp/MockSpeedController.cpp b/wpilibc/src/test/native/cpp/MockSpeedController.cpp
new file mode 100644
index 0000000..875fec1
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/MockSpeedController.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "MockSpeedController.h"
+
+using namespace frc;
+
+void MockSpeedController::Set(double speed) {
+  m_speed = m_isInverted ? -speed : speed;
+}
+
+double MockSpeedController::Get() const { return m_speed; }
+
+void MockSpeedController::SetInverted(bool isInverted) {
+  m_isInverted = isInverted;
+}
+
+bool MockSpeedController::GetInverted() const { return m_isInverted; }
+
+void MockSpeedController::Disable() { m_speed = 0; }
+
+void MockSpeedController::StopMotor() { Disable(); }
+
+void MockSpeedController::PIDWrite(double output) { Set(output); }
diff --git a/wpilibc/src/test/native/cpp/SlewRateLimiterTest.cpp b/wpilibc/src/test/native/cpp/SlewRateLimiterTest.cpp
new file mode 100644
index 0000000..ae253a7
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/SlewRateLimiterTest.cpp
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <thread>
+
+#include "frc/SlewRateLimiter.h"
+#include "gtest/gtest.h"
+
+TEST(SlewRateLimiterTest, SlewRateLimitTest) {
+  frc::SlewRateLimiter<units::meters> limiter(1_mps);
+
+  std::this_thread::sleep_for(std::chrono::milliseconds(1000));
+
+  EXPECT_TRUE(limiter.Calculate(2_m) < 2_m);
+}
+
+TEST(SlewRateLimiterTest, SlewRateNoLimitTest) {
+  frc::SlewRateLimiter<units::meters> limiter(1_mps);
+
+  std::this_thread::sleep_for(std::chrono::milliseconds(1000));
+
+  EXPECT_EQ(limiter.Calculate(0.5_m), 0.5_m);
+}
diff --git a/wpilibc/src/test/native/cpp/SpeedControllerGroupTest.cpp b/wpilibc/src/test/native/cpp/SpeedControllerGroupTest.cpp
new file mode 100644
index 0000000..cb81fc9
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/SpeedControllerGroupTest.cpp
@@ -0,0 +1,136 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/SpeedControllerGroup.h"  // NOLINT(build/include_order)
+
+#include <memory>
+#include <vector>
+
+#include "MockSpeedController.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+enum SpeedControllerGroupTestType { TEST_ONE, TEST_TWO, TEST_THREE };
+
+std::ostream& operator<<(std::ostream& os,
+                         const SpeedControllerGroupTestType& type) {
+  switch (type) {
+    case TEST_ONE:
+      os << "SpeedControllerGroup with one speed controller";
+      break;
+    case TEST_TWO:
+      os << "SpeedControllerGroup with two speed controllers";
+      break;
+    case TEST_THREE:
+      os << "SpeedControllerGroup with three speed controllers";
+      break;
+  }
+
+  return os;
+}
+
+/**
+ * A fixture used for SpeedControllerGroup testing.
+ */
+class SpeedControllerGroupTest
+    : public testing::TestWithParam<SpeedControllerGroupTestType> {
+ protected:
+  std::vector<MockSpeedController> m_speedControllers;
+  std::unique_ptr<SpeedControllerGroup> m_group;
+
+  void SetUp() override {
+    switch (GetParam()) {
+      case TEST_ONE: {
+        m_speedControllers.emplace_back();
+        m_group = std::make_unique<SpeedControllerGroup>(m_speedControllers[0]);
+        break;
+      }
+
+      case TEST_TWO: {
+        m_speedControllers.emplace_back();
+        m_speedControllers.emplace_back();
+        m_group = std::make_unique<SpeedControllerGroup>(m_speedControllers[0],
+                                                         m_speedControllers[1]);
+        break;
+      }
+
+      case TEST_THREE: {
+        m_speedControllers.emplace_back();
+        m_speedControllers.emplace_back();
+        m_speedControllers.emplace_back();
+        m_group = std::make_unique<SpeedControllerGroup>(m_speedControllers[0],
+                                                         m_speedControllers[1],
+                                                         m_speedControllers[2]);
+        break;
+      }
+    }
+  }
+};
+
+TEST_P(SpeedControllerGroupTest, Set) {
+  m_group->Set(1.0);
+
+  for (auto& speedController : m_speedControllers) {
+    EXPECT_FLOAT_EQ(speedController.Get(), 1.0);
+  }
+}
+
+TEST_P(SpeedControllerGroupTest, GetInverted) {
+  m_group->SetInverted(true);
+
+  EXPECT_TRUE(m_group->GetInverted());
+}
+
+TEST_P(SpeedControllerGroupTest, SetInvertedDoesNotModifySpeedControllers) {
+  for (auto& speedController : m_speedControllers) {
+    speedController.SetInverted(false);
+  }
+  m_group->SetInverted(true);
+
+  for (auto& speedController : m_speedControllers) {
+    EXPECT_EQ(speedController.GetInverted(), false);
+  }
+}
+
+TEST_P(SpeedControllerGroupTest, SetInvertedDoesInvert) {
+  m_group->SetInverted(true);
+  m_group->Set(1.0);
+
+  for (auto& speedController : m_speedControllers) {
+    EXPECT_FLOAT_EQ(speedController.Get(), -1.0);
+  }
+}
+
+TEST_P(SpeedControllerGroupTest, Disable) {
+  m_group->Set(1.0);
+  m_group->Disable();
+
+  for (auto& speedController : m_speedControllers) {
+    EXPECT_FLOAT_EQ(speedController.Get(), 0.0);
+  }
+}
+
+TEST_P(SpeedControllerGroupTest, StopMotor) {
+  m_group->Set(1.0);
+  m_group->StopMotor();
+
+  for (auto& speedController : m_speedControllers) {
+    EXPECT_FLOAT_EQ(speedController.Get(), 0.0);
+  }
+}
+
+TEST_P(SpeedControllerGroupTest, PIDWrite) {
+  m_group->PIDWrite(1.0);
+
+  for (auto& speedController : m_speedControllers) {
+    EXPECT_FLOAT_EQ(speedController.Get(), 1.0);
+  }
+}
+
+INSTANTIATE_TEST_SUITE_P(Test, SpeedControllerGroupTest,
+                         testing::Values(TEST_ONE, TEST_TWO, TEST_THREE));
diff --git a/wpilibc/src/test/native/cpp/WatchdogTest.cpp b/wpilibc/src/test/native/cpp/WatchdogTest.cpp
new file mode 100644
index 0000000..10ff996
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/WatchdogTest.cpp
@@ -0,0 +1,173 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/Watchdog.h"  // NOLINT(build/include_order)
+
+#include <stdint.h>
+
+#include <thread>
+
+#include <wpi/raw_ostream.h>
+
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+#ifdef __APPLE__
+TEST(WatchdogTest, DISABLED_EnableDisable) {
+#else
+TEST(WatchdogTest, EnableDisable) {
+#endif
+  uint32_t watchdogCounter = 0;
+
+  Watchdog watchdog(0.4_s, [&] { watchdogCounter++; });
+
+  wpi::outs() << "Run 1\n";
+  watchdog.Enable();
+  std::this_thread::sleep_for(std::chrono::milliseconds(200));
+  watchdog.Disable();
+
+  EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
+
+  wpi::outs() << "Run 2\n";
+  watchdogCounter = 0;
+  watchdog.Enable();
+  std::this_thread::sleep_for(std::chrono::milliseconds(600));
+  watchdog.Disable();
+
+  EXPECT_EQ(1u, watchdogCounter)
+      << "Watchdog either didn't trigger or triggered more than once";
+
+  wpi::outs() << "Run 3\n";
+  watchdogCounter = 0;
+  watchdog.Enable();
+  std::this_thread::sleep_for(std::chrono::milliseconds(1000));
+  watchdog.Disable();
+
+  EXPECT_EQ(1u, watchdogCounter)
+      << "Watchdog either didn't trigger or triggered more than once";
+}
+
+#ifdef __APPLE__
+TEST(WatchdogTest, DISABLED_Reset) {
+#else
+TEST(WatchdogTest, Reset) {
+#endif
+  uint32_t watchdogCounter = 0;
+
+  Watchdog watchdog(0.4_s, [&] { watchdogCounter++; });
+
+  watchdog.Enable();
+  std::this_thread::sleep_for(std::chrono::milliseconds(200));
+  watchdog.Reset();
+  std::this_thread::sleep_for(std::chrono::milliseconds(200));
+  watchdog.Disable();
+
+  EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
+}
+
+#ifdef __APPLE__
+TEST(WatchdogTest, DISABLED_SetTimeout) {
+#else
+TEST(WatchdogTest, SetTimeout) {
+#endif
+  uint32_t watchdogCounter = 0;
+
+  Watchdog watchdog(1.0_s, [&] { watchdogCounter++; });
+
+  watchdog.Enable();
+  std::this_thread::sleep_for(std::chrono::milliseconds(200));
+  watchdog.SetTimeout(0.2_s);
+
+  EXPECT_EQ(0.2, watchdog.GetTimeout());
+  EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
+
+  std::this_thread::sleep_for(std::chrono::milliseconds(300));
+  watchdog.Disable();
+
+  EXPECT_EQ(1u, watchdogCounter)
+      << "Watchdog either didn't trigger or triggered more than once";
+}
+
+#ifdef __APPLE__
+TEST(WatchdogTest, DISABLED_IsExpired) {
+#else
+TEST(WatchdogTest, IsExpired) {
+#endif
+  Watchdog watchdog(0.2_s, [] {});
+  EXPECT_FALSE(watchdog.IsExpired());
+  watchdog.Enable();
+
+  EXPECT_FALSE(watchdog.IsExpired());
+  std::this_thread::sleep_for(std::chrono::milliseconds(300));
+  EXPECT_TRUE(watchdog.IsExpired());
+
+  watchdog.Disable();
+  EXPECT_TRUE(watchdog.IsExpired());
+
+  watchdog.Reset();
+  EXPECT_FALSE(watchdog.IsExpired());
+}
+
+#ifdef __APPLE__
+TEST(WatchdogTest, DISABLED_Epochs) {
+#else
+TEST(WatchdogTest, Epochs) {
+#endif
+  uint32_t watchdogCounter = 0;
+
+  Watchdog watchdog(0.4_s, [&] { watchdogCounter++; });
+
+  wpi::outs() << "Run 1\n";
+  watchdog.Enable();
+  watchdog.AddEpoch("Epoch 1");
+  std::this_thread::sleep_for(std::chrono::milliseconds(100));
+  watchdog.AddEpoch("Epoch 2");
+  std::this_thread::sleep_for(std::chrono::milliseconds(100));
+  watchdog.AddEpoch("Epoch 3");
+  watchdog.Disable();
+
+  EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
+
+  wpi::outs() << "Run 2\n";
+  watchdog.Enable();
+  watchdog.AddEpoch("Epoch 1");
+  std::this_thread::sleep_for(std::chrono::milliseconds(200));
+  watchdog.Reset();
+  std::this_thread::sleep_for(std::chrono::milliseconds(200));
+  watchdog.AddEpoch("Epoch 2");
+  watchdog.Disable();
+
+  EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
+}
+
+#ifdef __APPLE__
+TEST(WatchdogTest, DISABLED_MultiWatchdog) {
+#else
+TEST(WatchdogTest, MultiWatchdog) {
+#endif
+  uint32_t watchdogCounter1 = 0;
+  uint32_t watchdogCounter2 = 0;
+
+  Watchdog watchdog1(0.2_s, [&] { watchdogCounter1++; });
+  Watchdog watchdog2(0.6_s, [&] { watchdogCounter2++; });
+
+  watchdog2.Enable();
+  std::this_thread::sleep_for(std::chrono::milliseconds(200));
+  EXPECT_EQ(0u, watchdogCounter1) << "Watchdog triggered early";
+  EXPECT_EQ(0u, watchdogCounter2) << "Watchdog triggered early";
+
+  // Sleep enough such that only the watchdog enabled later times out first
+  watchdog1.Enable();
+  std::this_thread::sleep_for(std::chrono::milliseconds(300));
+  watchdog1.Disable();
+  watchdog2.Disable();
+
+  EXPECT_EQ(1u, watchdogCounter1)
+      << "Watchdog either didn't trigger or triggered more than once";
+  EXPECT_EQ(0u, watchdogCounter2) << "Watchdog triggered early";
+}
diff --git a/wpilibc/src/test/native/cpp/controller/PIDInputOutputTest.cpp b/wpilibc/src/test/native/cpp/controller/PIDInputOutputTest.cpp
new file mode 100644
index 0000000..c68cb37
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/controller/PIDInputOutputTest.cpp
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/controller/PIDController.h"
+#include "gtest/gtest.h"
+
+class PIDInputOutputTest : public testing::Test {
+ protected:
+  frc2::PIDController* controller;
+
+  void SetUp() override { controller = new frc2::PIDController(0, 0, 0); }
+
+  void TearDown() override { delete controller; }
+};
+
+TEST_F(PIDInputOutputTest, ContinuousInputTest) {
+  controller->SetP(1);
+  controller->EnableContinuousInput(-180, 180);
+
+  EXPECT_TRUE(controller->Calculate(-179, 179) < 0);
+}
+
+TEST_F(PIDInputOutputTest, ProportionalGainOutputTest) {
+  controller->SetP(4);
+
+  EXPECT_DOUBLE_EQ(-0.1, controller->Calculate(0.025, 0));
+}
+
+TEST_F(PIDInputOutputTest, IntegralGainOutputTest) {
+  controller->SetI(4);
+
+  double out = 0;
+
+  for (int i = 0; i < 5; i++) {
+    out = controller->Calculate(0.025, 0);
+  }
+
+  EXPECT_DOUBLE_EQ(-0.5 * controller->GetPeriod().to<double>(), out);
+}
+
+TEST_F(PIDInputOutputTest, DerivativeGainOutputTest) {
+  controller->SetD(4);
+
+  controller->Calculate(0, 0);
+
+  EXPECT_DOUBLE_EQ(-10_ms / controller->GetPeriod(),
+                   controller->Calculate(0.0025, 0));
+}
diff --git a/wpilibc/src/test/native/cpp/controller/PIDToleranceTest.cpp b/wpilibc/src/test/native/cpp/controller/PIDToleranceTest.cpp
new file mode 100644
index 0000000..3251098
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/controller/PIDToleranceTest.cpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/controller/PIDController.h"
+#include "gtest/gtest.h"
+
+static constexpr double kSetpoint = 50.0;
+static constexpr double kRange = 200;
+static constexpr double kTolerance = 10.0;
+
+TEST(PIDToleranceTest, InitialTolerance) {
+  frc2::PIDController controller{0.5, 0.0, 0.0};
+  controller.EnableContinuousInput(-kRange / 2, kRange / 2);
+
+  EXPECT_TRUE(controller.AtSetpoint());
+}
+
+TEST(PIDToleranceTest, AbsoluteTolerance) {
+  frc2::PIDController controller{0.5, 0.0, 0.0};
+  controller.EnableContinuousInput(-kRange / 2, kRange / 2);
+
+  controller.SetTolerance(kTolerance);
+  controller.SetSetpoint(kSetpoint);
+
+  controller.Calculate(0.0);
+
+  EXPECT_FALSE(controller.AtSetpoint())
+      << "Error was in tolerance when it should not have been. Error was "
+      << controller.GetPositionError();
+
+  controller.Calculate(kSetpoint + kTolerance / 2);
+
+  EXPECT_TRUE(controller.AtSetpoint())
+      << "Error was not in tolerance when it should have been. Error was "
+      << controller.GetPositionError();
+
+  controller.Calculate(kSetpoint + 10 * kTolerance);
+
+  EXPECT_FALSE(controller.AtSetpoint())
+      << "Error was in tolerance when it should not have been. Error was "
+      << controller.GetPositionError();
+}
diff --git a/wpilibc/src/test/native/cpp/controller/RamseteControllerTest.cpp b/wpilibc/src/test/native/cpp/controller/RamseteControllerTest.cpp
new file mode 100644
index 0000000..a600054
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/controller/RamseteControllerTest.cpp
@@ -0,0 +1,57 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <wpi/math>
+
+#include "frc/controller/RamseteController.h"
+#include "frc/trajectory/TrajectoryGenerator.h"
+#include "gtest/gtest.h"
+
+#define EXPECT_NEAR_UNITS(val1, val2, eps) \
+  EXPECT_LE(units::math::abs(val1 - val2), eps)
+
+static constexpr units::meter_t kTolerance{1 / 12.0};
+static constexpr units::radian_t kAngularTolerance{2.0 * wpi::math::pi / 180.0};
+
+units::radian_t boundRadians(units::radian_t value) {
+  while (value > units::radian_t{wpi::math::pi}) {
+    value -= units::radian_t{wpi::math::pi * 2};
+  }
+  while (value <= units::radian_t{-wpi::math::pi}) {
+    value += units::radian_t{wpi::math::pi * 2};
+  }
+  return value;
+}
+
+TEST(RamseteControllerTest, ReachesReference) {
+  frc::RamseteController controller{2.0, 0.7};
+  frc::Pose2d robotPose{2.7_m, 23_m, frc::Rotation2d{0_deg}};
+
+  auto waypoints = std::vector{frc::Pose2d{2.75_m, 22.521_m, 0_rad},
+                               frc::Pose2d{24.73_m, 19.68_m, 5.846_rad}};
+  auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
+      waypoints, {8.8_mps, 0.1_mps_sq});
+
+  constexpr auto kDt = 0.02_s;
+  auto totalTime = trajectory.TotalTime();
+  for (size_t i = 0; i < (totalTime / kDt).to<double>(); ++i) {
+    auto state = trajectory.Sample(kDt * i);
+    auto [vx, vy, omega] = controller.Calculate(robotPose, state);
+    static_cast<void>(vy);
+
+    robotPose = robotPose.Exp(frc::Twist2d{vx * kDt, 0_m, omega * kDt});
+  }
+
+  auto& endPose = trajectory.States().back().pose;
+  EXPECT_NEAR_UNITS(endPose.Translation().X(), robotPose.Translation().X(),
+                    kTolerance);
+  EXPECT_NEAR_UNITS(endPose.Translation().Y(), robotPose.Translation().Y(),
+                    kTolerance);
+  EXPECT_NEAR_UNITS(boundRadians(endPose.Rotation().Radians() -
+                                 robotPose.Rotation().Radians()),
+                    0_rad, kAngularTolerance);
+}
diff --git a/wpilibc/src/test/native/cpp/drive/DriveTest.cpp b/wpilibc/src/test/native/cpp/drive/DriveTest.cpp
new file mode 100644
index 0000000..1ebb6b3
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/drive/DriveTest.cpp
@@ -0,0 +1,190 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "MockSpeedController.h"
+#include "frc/RobotDrive.h"
+#include "frc/drive/DifferentialDrive.h"
+#include "frc/drive/MecanumDrive.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class DriveTest : public testing::Test {
+ protected:
+  MockSpeedController m_rdFrontLeft;
+  MockSpeedController m_rdRearLeft;
+  MockSpeedController m_rdFrontRight;
+  MockSpeedController m_rdRearRight;
+  MockSpeedController m_frontLeft;
+  MockSpeedController m_rearLeft;
+  MockSpeedController m_frontRight;
+  MockSpeedController m_rearRight;
+  frc::RobotDrive m_robotDrive{m_rdFrontLeft, m_rdRearLeft, m_rdFrontRight,
+                               m_rdRearRight};
+  frc::DifferentialDrive m_differentialDrive{m_frontLeft, m_frontRight};
+  frc::MecanumDrive m_mecanumDrive{m_frontLeft, m_rearLeft, m_frontRight,
+                                   m_rearRight};
+
+  double m_testJoystickValues[9] = {-1.0, -0.9, -0.5, -0.01, 0.0,
+                                    0.01, 0.5,  0.9,  1.0};
+  double m_testGyroValues[19] = {0,    45,   90,   135,  180, 225,  270,
+                                 305,  360,  540,  -45,  -90, -135, -180,
+                                 -225, -270, -305, -360, -540};
+};
+
+TEST_F(DriveTest, TankDrive) {
+  int joystickSize = sizeof(m_testJoystickValues) / sizeof(double);
+  double leftJoystick, rightJoystick;
+  m_differentialDrive.SetDeadband(0.0);
+  m_differentialDrive.SetSafetyEnabled(false);
+  m_mecanumDrive.SetSafetyEnabled(false);
+  m_robotDrive.SetSafetyEnabled(false);
+  for (int i = 0; i < joystickSize; i++) {
+    for (int j = 0; j < joystickSize; j++) {
+      leftJoystick = m_testJoystickValues[i];
+      rightJoystick = m_testJoystickValues[j];
+      m_robotDrive.TankDrive(leftJoystick, rightJoystick, false);
+      m_differentialDrive.TankDrive(leftJoystick, rightJoystick, false);
+      ASSERT_NEAR(m_rdFrontLeft.Get(), m_frontLeft.Get(), 0.01);
+      ASSERT_NEAR(m_rdFrontRight.Get(), m_frontRight.Get(), 0.01);
+    }
+  }
+}
+
+TEST_F(DriveTest, TankDriveSquared) {
+  int joystickSize = sizeof(m_testJoystickValues) / sizeof(double);
+  double leftJoystick, rightJoystick;
+  m_differentialDrive.SetDeadband(0.0);
+  m_differentialDrive.SetSafetyEnabled(false);
+  m_mecanumDrive.SetSafetyEnabled(false);
+  m_robotDrive.SetSafetyEnabled(false);
+  for (int i = 0; i < joystickSize; i++) {
+    for (int j = 0; j < joystickSize; j++) {
+      leftJoystick = m_testJoystickValues[i];
+      rightJoystick = m_testJoystickValues[j];
+      m_robotDrive.TankDrive(leftJoystick, rightJoystick, true);
+      m_differentialDrive.TankDrive(leftJoystick, rightJoystick, true);
+      ASSERT_NEAR(m_rdFrontLeft.Get(), m_frontLeft.Get(), 0.01);
+      ASSERT_NEAR(m_rdFrontRight.Get(), m_frontRight.Get(), 0.01);
+    }
+  }
+}
+
+TEST_F(DriveTest, ArcadeDriveSquared) {
+  int joystickSize = sizeof(m_testJoystickValues) / sizeof(double);
+  double moveJoystick, rotateJoystick;
+  m_differentialDrive.SetDeadband(0.0);
+  m_differentialDrive.SetSafetyEnabled(false);
+  m_mecanumDrive.SetSafetyEnabled(false);
+  m_robotDrive.SetSafetyEnabled(false);
+  for (int i = 0; i < joystickSize; i++) {
+    for (int j = 0; j < joystickSize; j++) {
+      moveJoystick = m_testJoystickValues[i];
+      rotateJoystick = m_testJoystickValues[j];
+      m_robotDrive.ArcadeDrive(moveJoystick, rotateJoystick, true);
+      m_differentialDrive.ArcadeDrive(moveJoystick, -rotateJoystick, true);
+      ASSERT_NEAR(m_rdFrontLeft.Get(), m_frontLeft.Get(), 0.01);
+      ASSERT_NEAR(m_rdFrontRight.Get(), m_frontRight.Get(), 0.01);
+    }
+  }
+}
+
+TEST_F(DriveTest, ArcadeDrive) {
+  int joystickSize = sizeof(m_testJoystickValues) / sizeof(double);
+  double moveJoystick, rotateJoystick;
+  m_differentialDrive.SetDeadband(0.0);
+  m_differentialDrive.SetSafetyEnabled(false);
+  m_mecanumDrive.SetSafetyEnabled(false);
+  m_robotDrive.SetSafetyEnabled(false);
+  for (int i = 0; i < joystickSize; i++) {
+    for (int j = 0; j < joystickSize; j++) {
+      moveJoystick = m_testJoystickValues[i];
+      rotateJoystick = m_testJoystickValues[j];
+      m_robotDrive.ArcadeDrive(moveJoystick, rotateJoystick, false);
+      m_differentialDrive.ArcadeDrive(moveJoystick, -rotateJoystick, false);
+      ASSERT_NEAR(m_rdFrontLeft.Get(), m_frontLeft.Get(), 0.01);
+      ASSERT_NEAR(m_rdFrontRight.Get(), m_frontRight.Get(), 0.01);
+    }
+  }
+}
+
+TEST_F(DriveTest, MecanumCartesian) {
+  int joystickSize = sizeof(m_testJoystickValues) / sizeof(double);
+  int gyroSize = sizeof(m_testGyroValues) / sizeof(double);
+  double xJoystick, yJoystick, rotateJoystick, gyroValue;
+  m_mecanumDrive.SetDeadband(0.0);
+  m_mecanumDrive.SetSafetyEnabled(false);
+  m_differentialDrive.SetSafetyEnabled(false);
+  m_robotDrive.SetSafetyEnabled(false);
+  for (int i = 0; i < joystickSize; i++) {
+    for (int j = 0; j < joystickSize; j++) {
+      for (int k = 0; k < joystickSize; k++) {
+        for (int l = 0; l < gyroSize; l++) {
+          xJoystick = m_testJoystickValues[i];
+          yJoystick = m_testJoystickValues[j];
+          rotateJoystick = m_testJoystickValues[k];
+          gyroValue = m_testGyroValues[l];
+          m_robotDrive.MecanumDrive_Cartesian(xJoystick, yJoystick,
+                                              rotateJoystick, gyroValue);
+          m_mecanumDrive.DriveCartesian(xJoystick, -yJoystick, rotateJoystick,
+                                        -gyroValue);
+          ASSERT_NEAR(m_rdFrontLeft.Get(), m_frontLeft.Get(), 0.01)
+              << "X: " << xJoystick << " Y: " << yJoystick
+              << " Rotate: " << rotateJoystick << " Gyro: " << gyroValue;
+          ASSERT_NEAR(m_rdFrontRight.Get(), -m_frontRight.Get(), 0.01)
+              << "X: " << xJoystick << " Y: " << yJoystick
+              << " Rotate: " << rotateJoystick << " Gyro: " << gyroValue;
+          ASSERT_NEAR(m_rdRearLeft.Get(), m_rearLeft.Get(), 0.01)
+              << "X: " << xJoystick << " Y: " << yJoystick
+              << " Rotate: " << rotateJoystick << " Gyro: " << gyroValue;
+          ASSERT_NEAR(m_rdRearRight.Get(), -m_rearRight.Get(), 0.01)
+              << "X: " << xJoystick << " Y: " << yJoystick
+              << " Rotate: " << rotateJoystick << " Gyro: " << gyroValue;
+        }
+      }
+    }
+  }
+}
+
+TEST_F(DriveTest, MecanumPolar) {
+  int joystickSize = sizeof(m_testJoystickValues) / sizeof(double);
+  int gyroSize = sizeof(m_testGyroValues) / sizeof(double);
+  double magnitudeJoystick, directionJoystick, rotateJoystick;
+  m_mecanumDrive.SetDeadband(0.0);
+  m_mecanumDrive.SetSafetyEnabled(false);
+  m_differentialDrive.SetSafetyEnabled(false);
+  m_robotDrive.SetSafetyEnabled(false);
+  for (int i = 0; i < joystickSize; i++) {
+    for (int j = 0; j < gyroSize; j++) {
+      for (int k = 0; k < joystickSize; k++) {
+        magnitudeJoystick = m_testJoystickValues[i];
+        directionJoystick = m_testGyroValues[j];
+        rotateJoystick = m_testJoystickValues[k];
+        m_robotDrive.MecanumDrive_Polar(magnitudeJoystick, directionJoystick,
+                                        rotateJoystick);
+        m_mecanumDrive.DrivePolar(magnitudeJoystick, directionJoystick,
+                                  rotateJoystick);
+        ASSERT_NEAR(m_rdFrontLeft.Get(), m_frontLeft.Get(), 0.01)
+            << "Magnitude: " << magnitudeJoystick
+            << " Direction: " << directionJoystick
+            << " Rotate: " << rotateJoystick;
+        ASSERT_NEAR(m_rdFrontRight.Get(), -m_frontRight.Get(), 0.01)
+            << "Magnitude: " << magnitudeJoystick
+            << " Direction: " << directionJoystick
+            << " Rotate: " << rotateJoystick;
+        ASSERT_NEAR(m_rdRearLeft.Get(), m_rearLeft.Get(), 0.01)
+            << "Magnitude: " << magnitudeJoystick
+            << " Direction: " << directionJoystick
+            << " Rotate: " << rotateJoystick;
+        ASSERT_NEAR(m_rdRearRight.Get(), -m_rearRight.Get(), 0.01)
+            << "Magnitude: " << magnitudeJoystick
+            << " Direction: " << directionJoystick
+            << " Rotate: " << rotateJoystick;
+      }
+    }
+  }
+}
diff --git a/wpilibc/src/test/native/cpp/geometry/Pose2dTest.cpp b/wpilibc/src/test/native/cpp/geometry/Pose2dTest.cpp
new file mode 100644
index 0000000..8b5f674
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/geometry/Pose2dTest.cpp
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <cmath>
+
+#include "frc/geometry/Pose2d.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static constexpr double kEpsilon = 1E-9;
+
+TEST(Pose2dTest, TransformBy) {
+  const Pose2d initial{1_m, 2_m, Rotation2d(45.0_deg)};
+  const Transform2d transform{Translation2d{5.0_m, 0.0_m}, Rotation2d(5.0_deg)};
+
+  const auto transformed = initial + transform;
+
+  EXPECT_NEAR(transformed.Translation().X().to<double>(),
+              1 + 5 / std::sqrt(2.0), kEpsilon);
+  EXPECT_NEAR(transformed.Translation().Y().to<double>(),
+              2 + 5 / std::sqrt(2.0), kEpsilon);
+  EXPECT_NEAR(transformed.Rotation().Degrees().to<double>(), 50.0, kEpsilon);
+}
+
+TEST(Pose2dTest, RelativeTo) {
+  const Pose2d initial{0_m, 0_m, Rotation2d(45.0_deg)};
+  const Pose2d final{5_m, 5_m, Rotation2d(45.0_deg)};
+
+  const auto finalRelativeToInitial = final.RelativeTo(initial);
+
+  EXPECT_NEAR(finalRelativeToInitial.Translation().X().to<double>(),
+              5.0 * std::sqrt(2.0), kEpsilon);
+  EXPECT_NEAR(finalRelativeToInitial.Translation().Y().to<double>(), 0.0,
+              kEpsilon);
+  EXPECT_NEAR(finalRelativeToInitial.Rotation().Degrees().to<double>(), 0.0,
+              kEpsilon);
+}
+
+TEST(Pose2dTest, Equality) {
+  const Pose2d a{0_m, 5_m, Rotation2d(43_deg)};
+  const Pose2d b{0_m, 5_m, Rotation2d(43_deg)};
+  EXPECT_TRUE(a == b);
+}
+
+TEST(Pose2dTest, Inequality) {
+  const Pose2d a{0_m, 5_m, Rotation2d(43_deg)};
+  const Pose2d b{0_m, 5_ft, Rotation2d(43_deg)};
+  EXPECT_TRUE(a != b);
+}
+
+TEST(Pose2dTest, Minus) {
+  const Pose2d initial{0_m, 0_m, Rotation2d(45.0_deg)};
+  const Pose2d final{5_m, 5_m, Rotation2d(45.0_deg)};
+
+  const auto transform = final - initial;
+
+  EXPECT_NEAR(transform.Translation().X().to<double>(), 5.0 * std::sqrt(2.0),
+              kEpsilon);
+  EXPECT_NEAR(transform.Translation().Y().to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(transform.Rotation().Degrees().to<double>(), 0.0, kEpsilon);
+}
diff --git a/wpilibc/src/test/native/cpp/geometry/Rotation2dTest.cpp b/wpilibc/src/test/native/cpp/geometry/Rotation2dTest.cpp
new file mode 100644
index 0000000..ba80787
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/geometry/Rotation2dTest.cpp
@@ -0,0 +1,67 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <cmath>
+
+#include <wpi/math>
+
+#include "frc/geometry/Rotation2d.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static constexpr double kEpsilon = 1E-9;
+
+TEST(Rotation2dTest, RadiansToDegrees) {
+  const Rotation2d one{units::radian_t(wpi::math::pi / 3)};
+  const Rotation2d two{units::radian_t(wpi::math::pi / 4)};
+
+  EXPECT_NEAR(one.Degrees().to<double>(), 60.0, kEpsilon);
+  EXPECT_NEAR(two.Degrees().to<double>(), 45.0, kEpsilon);
+}
+
+TEST(Rotation2dTest, DegreesToRadians) {
+  const auto one = Rotation2d(45.0_deg);
+  const auto two = Rotation2d(30.0_deg);
+
+  EXPECT_NEAR(one.Radians().to<double>(), wpi::math::pi / 4.0, kEpsilon);
+  EXPECT_NEAR(two.Radians().to<double>(), wpi::math::pi / 6.0, kEpsilon);
+}
+
+TEST(Rotation2dTest, RotateByFromZero) {
+  const Rotation2d zero;
+  auto sum = zero + Rotation2d(90.0_deg);
+
+  EXPECT_NEAR(sum.Radians().to<double>(), wpi::math::pi / 2.0, kEpsilon);
+  EXPECT_NEAR(sum.Degrees().to<double>(), 90.0, kEpsilon);
+}
+
+TEST(Rotation2dTest, RotateByNonZero) {
+  auto rot = Rotation2d(90.0_deg);
+  rot += Rotation2d(30.0_deg);
+
+  EXPECT_NEAR(rot.Degrees().to<double>(), 120.0, kEpsilon);
+}
+
+TEST(Rotation2dTest, Minus) {
+  const auto one = Rotation2d(70.0_deg);
+  const auto two = Rotation2d(30.0_deg);
+
+  EXPECT_NEAR((one - two).Degrees().to<double>(), 40.0, kEpsilon);
+}
+
+TEST(Rotation2dTest, Equality) {
+  const auto one = Rotation2d(43_deg);
+  const auto two = Rotation2d(43_deg);
+  EXPECT_TRUE(one == two);
+}
+
+TEST(Rotation2dTest, Inequality) {
+  const auto one = Rotation2d(43_deg);
+  const auto two = Rotation2d(43.5_deg);
+  EXPECT_TRUE(one != two);
+}
diff --git a/wpilibc/src/test/native/cpp/geometry/Translation2dTest.cpp b/wpilibc/src/test/native/cpp/geometry/Translation2dTest.cpp
new file mode 100644
index 0000000..99fced7
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/geometry/Translation2dTest.cpp
@@ -0,0 +1,90 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <cmath>
+
+#include "frc/geometry/Translation2d.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static constexpr double kEpsilon = 1E-9;
+
+TEST(Translation2dTest, Sum) {
+  const Translation2d one{1.0_m, 3.0_m};
+  const Translation2d two{2.0_m, 5.0_m};
+
+  const auto sum = one + two;
+
+  EXPECT_NEAR(sum.X().to<double>(), 3.0, kEpsilon);
+  EXPECT_NEAR(sum.Y().to<double>(), 8.0, kEpsilon);
+}
+
+TEST(Translation2dTest, Difference) {
+  const Translation2d one{1.0_m, 3.0_m};
+  const Translation2d two{2.0_m, 5.0_m};
+
+  const auto difference = one - two;
+
+  EXPECT_NEAR(difference.X().to<double>(), -1.0, kEpsilon);
+  EXPECT_NEAR(difference.Y().to<double>(), -2.0, kEpsilon);
+}
+
+TEST(Translation2dTest, RotateBy) {
+  const Translation2d another{3.0_m, 0.0_m};
+  const auto rotated = another.RotateBy(Rotation2d(90.0_deg));
+
+  EXPECT_NEAR(rotated.X().to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(rotated.Y().to<double>(), 3.0, kEpsilon);
+}
+
+TEST(Translation2dTest, Multiplication) {
+  const Translation2d original{3.0_m, 5.0_m};
+  const auto mult = original * 3;
+
+  EXPECT_NEAR(mult.X().to<double>(), 9.0, kEpsilon);
+  EXPECT_NEAR(mult.Y().to<double>(), 15.0, kEpsilon);
+}
+
+TEST(Translation2d, Division) {
+  const Translation2d original{3.0_m, 5.0_m};
+  const auto div = original / 2;
+
+  EXPECT_NEAR(div.X().to<double>(), 1.5, kEpsilon);
+  EXPECT_NEAR(div.Y().to<double>(), 2.5, kEpsilon);
+}
+
+TEST(Translation2dTest, Norm) {
+  const Translation2d one{3.0_m, 5.0_m};
+  EXPECT_NEAR(one.Norm().to<double>(), std::hypot(3, 5), kEpsilon);
+}
+
+TEST(Translation2dTest, Distance) {
+  const Translation2d one{1_m, 1_m};
+  const Translation2d two{6_m, 6_m};
+  EXPECT_NEAR(one.Distance(two).to<double>(), 5 * std::sqrt(2), kEpsilon);
+}
+
+TEST(Translation2dTest, UnaryMinus) {
+  const Translation2d original{-4.5_m, 7_m};
+  const auto inverted = -original;
+
+  EXPECT_NEAR(inverted.X().to<double>(), 4.5, kEpsilon);
+  EXPECT_NEAR(inverted.Y().to<double>(), -7, kEpsilon);
+}
+
+TEST(Translation2dTest, Equality) {
+  const Translation2d one{9_m, 5.5_m};
+  const Translation2d two{9_m, 5.5_m};
+  EXPECT_TRUE(one == two);
+}
+
+TEST(Translation2dTest, Inequality) {
+  const Translation2d one{9_m, 5.5_m};
+  const Translation2d two{9_m, 5.7_m};
+  EXPECT_TRUE(one != two);
+}
diff --git a/wpilibc/src/test/native/cpp/geometry/Twist2dTest.cpp b/wpilibc/src/test/native/cpp/geometry/Twist2dTest.cpp
new file mode 100644
index 0000000..faf36d9
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/geometry/Twist2dTest.cpp
@@ -0,0 +1,69 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <cmath>
+
+#include <wpi/math>
+
+#include "frc/geometry/Pose2d.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static constexpr double kEpsilon = 1E-9;
+
+TEST(Twist2dTest, Straight) {
+  const Twist2d straight{5.0_m, 0.0_m, 0.0_rad};
+  const auto straightPose = Pose2d().Exp(straight);
+
+  EXPECT_NEAR(straightPose.Translation().X().to<double>(), 5.0, kEpsilon);
+  EXPECT_NEAR(straightPose.Translation().Y().to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(straightPose.Rotation().Radians().to<double>(), 0.0, kEpsilon);
+}
+
+TEST(Twist2dTest, QuarterCircle) {
+  const Twist2d quarterCircle{5.0_m / 2.0 * wpi::math::pi, 0_m,
+                              units::radian_t(wpi::math::pi / 2.0)};
+  const auto quarterCirclePose = Pose2d().Exp(quarterCircle);
+
+  EXPECT_NEAR(quarterCirclePose.Translation().X().to<double>(), 5.0, kEpsilon);
+  EXPECT_NEAR(quarterCirclePose.Translation().Y().to<double>(), 5.0, kEpsilon);
+  EXPECT_NEAR(quarterCirclePose.Rotation().Degrees().to<double>(), 90.0,
+              kEpsilon);
+}
+
+TEST(Twist2dTest, DiagonalNoDtheta) {
+  const Twist2d diagonal{2.0_m, 2.0_m, 0.0_deg};
+  const auto diagonalPose = Pose2d().Exp(diagonal);
+
+  EXPECT_NEAR(diagonalPose.Translation().X().to<double>(), 2.0, kEpsilon);
+  EXPECT_NEAR(diagonalPose.Translation().Y().to<double>(), 2.0, kEpsilon);
+  EXPECT_NEAR(diagonalPose.Rotation().Degrees().to<double>(), 0.0, kEpsilon);
+}
+
+TEST(Twist2dTest, Equality) {
+  const Twist2d one{5.0_m, 1.0_m, 3.0_rad};
+  const Twist2d two{5.0_m, 1.0_m, 3.0_rad};
+  EXPECT_TRUE(one == two);
+}
+
+TEST(Twist2dTest, Inequality) {
+  const Twist2d one{5.0_m, 1.0_m, 3.0_rad};
+  const Twist2d two{5.0_m, 1.2_m, 3.0_rad};
+  EXPECT_TRUE(one != two);
+}
+
+TEST(Twist2dTest, Pose2dLog) {
+  const Pose2d end{5_m, 5_m, Rotation2d(90_deg)};
+  const Pose2d start{};
+
+  const auto twist = start.Log(end);
+
+  EXPECT_NEAR(twist.dx.to<double>(), 5 / 2.0 * wpi::math::pi, kEpsilon);
+  EXPECT_NEAR(twist.dy.to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(twist.dtheta.to<double>(), wpi::math::pi / 2.0, kEpsilon);
+}
diff --git a/wpilibc/src/test/native/cpp/kinematics/ChassisSpeedsTest.cpp b/wpilibc/src/test/native/cpp/kinematics/ChassisSpeedsTest.cpp
new file mode 100644
index 0000000..3fb63fb
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/kinematics/ChassisSpeedsTest.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/kinematics/ChassisSpeeds.h"
+#include "gtest/gtest.h"
+
+static constexpr double kEpsilon = 1E-9;
+
+TEST(ChassisSpeeds, FieldRelativeConstruction) {
+  const auto chassisSpeeds = frc::ChassisSpeeds::FromFieldRelativeSpeeds(
+      1.0_mps, 0.0_mps, 0.5_rad_per_s, frc::Rotation2d(-90.0_deg));
+
+  EXPECT_NEAR(0.0, chassisSpeeds.vx.to<double>(), kEpsilon);
+  EXPECT_NEAR(1.0, chassisSpeeds.vy.to<double>(), kEpsilon);
+  EXPECT_NEAR(0.5, chassisSpeeds.omega.to<double>(), kEpsilon);
+}
diff --git a/wpilibc/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp b/wpilibc/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp
new file mode 100644
index 0000000..ad0d3c7
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <units/units.h>
+#include <wpi/math>
+
+#include "frc/kinematics/ChassisSpeeds.h"
+#include "frc/kinematics/DifferentialDriveKinematics.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static constexpr double kEpsilon = 1E-9;
+
+TEST(DifferentialDriveKinematics, InverseKinematicsFromZero) {
+  const DifferentialDriveKinematics kinematics{0.381_m * 2};
+  const ChassisSpeeds chassisSpeeds;
+  const auto wheelSpeeds = kinematics.ToWheelSpeeds(chassisSpeeds);
+
+  EXPECT_NEAR(wheelSpeeds.left.to<double>(), 0, kEpsilon);
+  EXPECT_NEAR(wheelSpeeds.right.to<double>(), 0, kEpsilon);
+}
+
+TEST(DifferentialDriveKinematics, ForwardKinematicsFromZero) {
+  const DifferentialDriveKinematics kinematics{0.381_m * 2};
+  const DifferentialDriveWheelSpeeds wheelSpeeds;
+  const auto chassisSpeeds = kinematics.ToChassisSpeeds(wheelSpeeds);
+
+  EXPECT_NEAR(chassisSpeeds.vx.to<double>(), 0, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.vy.to<double>(), 0, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.omega.to<double>(), 0, kEpsilon);
+}
+
+TEST(DifferentialDriveKinematics, InverseKinematicsForStraightLine) {
+  const DifferentialDriveKinematics kinematics{0.381_m * 2};
+  const ChassisSpeeds chassisSpeeds{3.0_mps, 0_mps, 0_rad_per_s};
+  const auto wheelSpeeds = kinematics.ToWheelSpeeds(chassisSpeeds);
+
+  EXPECT_NEAR(wheelSpeeds.left.to<double>(), 3, kEpsilon);
+  EXPECT_NEAR(wheelSpeeds.right.to<double>(), 3, kEpsilon);
+}
+
+TEST(DifferentialDriveKinematics, ForwardKinematicsForStraightLine) {
+  const DifferentialDriveKinematics kinematics{0.381_m * 2};
+  const DifferentialDriveWheelSpeeds wheelSpeeds{3.0_mps, 3.0_mps};
+  const auto chassisSpeeds = kinematics.ToChassisSpeeds(wheelSpeeds);
+
+  EXPECT_NEAR(chassisSpeeds.vx.to<double>(), 3, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.vy.to<double>(), 0, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.omega.to<double>(), 0, kEpsilon);
+}
+
+TEST(DifferentialDriveKinematics, InverseKinematicsForRotateInPlace) {
+  const DifferentialDriveKinematics kinematics{0.381_m * 2};
+  const ChassisSpeeds chassisSpeeds{0.0_mps, 0.0_mps,
+                                    units::radians_per_second_t{wpi::math::pi}};
+  const auto wheelSpeeds = kinematics.ToWheelSpeeds(chassisSpeeds);
+
+  EXPECT_NEAR(wheelSpeeds.left.to<double>(), -0.381 * wpi::math::pi, kEpsilon);
+  EXPECT_NEAR(wheelSpeeds.right.to<double>(), +0.381 * wpi::math::pi, kEpsilon);
+}
+
+TEST(DifferentialDriveKinematics, ForwardKinematicsForRotateInPlace) {
+  const DifferentialDriveKinematics kinematics{0.381_m * 2};
+  const DifferentialDriveWheelSpeeds wheelSpeeds{
+      units::meters_per_second_t(+0.381 * wpi::math::pi),
+      units::meters_per_second_t(-0.381 * wpi::math::pi)};
+  const auto chassisSpeeds = kinematics.ToChassisSpeeds(wheelSpeeds);
+
+  EXPECT_NEAR(chassisSpeeds.vx.to<double>(), 0, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.vy.to<double>(), 0, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.omega.to<double>(), -wpi::math::pi, kEpsilon);
+}
diff --git a/wpilibc/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp b/wpilibc/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp
new file mode 100644
index 0000000..8acaf92
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <wpi/math>
+
+#include "frc/kinematics/DifferentialDriveKinematics.h"
+#include "frc/kinematics/DifferentialDriveOdometry.h"
+#include "gtest/gtest.h"
+
+static constexpr double kEpsilon = 1E-9;
+
+using namespace frc;
+
+TEST(DifferentialDriveOdometry, EncoderDistances) {
+  DifferentialDriveOdometry odometry{Rotation2d(45_deg)};
+
+  const auto& pose = odometry.Update(Rotation2d(135_deg), 0_m,
+                                     units::meter_t(5 * wpi::math::pi));
+
+  EXPECT_NEAR(pose.Translation().X().to<double>(), 5.0, kEpsilon);
+  EXPECT_NEAR(pose.Translation().Y().to<double>(), 5.0, kEpsilon);
+  EXPECT_NEAR(pose.Rotation().Degrees().to<double>(), 90.0, kEpsilon);
+}
diff --git a/wpilibc/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp b/wpilibc/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp
new file mode 100644
index 0000000..75f395d
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp
@@ -0,0 +1,230 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <units/units.h>
+#include <wpi/math>
+
+#include "frc/geometry/Translation2d.h"
+#include "frc/kinematics/MecanumDriveKinematics.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class MecanumDriveKinematicsTest : public ::testing::Test {
+ protected:
+  Translation2d m_fl{12_m, 12_m};
+  Translation2d m_fr{12_m, -12_m};
+  Translation2d m_bl{-12_m, 12_m};
+  Translation2d m_br{-12_m, -12_m};
+
+  MecanumDriveKinematics kinematics{m_fl, m_fr, m_bl, m_br};
+};
+
+TEST_F(MecanumDriveKinematicsTest, StraightLineInverseKinematics) {
+  ChassisSpeeds speeds{5_mps, 0_mps, 0_rad_per_s};
+  auto moduleStates = kinematics.ToWheelSpeeds(speeds);
+
+  /*
+    By equation (13.12) of the state-space-guide, the wheel speeds should
+    be as follows:
+    velocities: fl 3.535534 fr 3.535534 rl 3.535534 rr 3.535534
+  */
+
+  EXPECT_NEAR(3.536, moduleStates.frontLeft.to<double>(), 0.1);
+  EXPECT_NEAR(3.536, moduleStates.frontRight.to<double>(), 0.1);
+  EXPECT_NEAR(3.536, moduleStates.rearLeft.to<double>(), 0.1);
+  EXPECT_NEAR(3.536, moduleStates.rearRight.to<double>(), 0.1);
+}
+
+TEST_F(MecanumDriveKinematicsTest, StraightLineForwardKinematics) {
+  MecanumDriveWheelSpeeds wheelSpeeds{3.536_mps, 3.536_mps, 3.536_mps,
+                                      3.536_mps};
+  auto chassisSpeeds = kinematics.ToChassisSpeeds(wheelSpeeds);
+
+  /*
+  By equation (13.13) of the state-space-guide, the chassis motion from wheel
+  velocities: fl 3.535534 fr 3.535534 rl 3.535534 rr 3.535534 will be
+  [[5][0][0]]
+  */
+
+  EXPECT_NEAR(5.0, chassisSpeeds.vx.to<double>(), 0.1);
+  EXPECT_NEAR(0.0, chassisSpeeds.vy.to<double>(), 0.1);
+  EXPECT_NEAR(0.0, chassisSpeeds.omega.to<double>(), 0.1);
+}
+
+TEST_F(MecanumDriveKinematicsTest, StrafeInverseKinematics) {
+  ChassisSpeeds speeds{0_mps, 4_mps, 0_rad_per_s};
+  auto moduleStates = kinematics.ToWheelSpeeds(speeds);
+
+  /*
+  By equation (13.12) of the state-space-guide, the wheel speeds should
+  be as follows:
+  velocities: fl -2.828427 fr 2.828427 rl 2.828427 rr -2.828427
+  */
+
+  EXPECT_NEAR(-2.828427, moduleStates.frontLeft.to<double>(), 0.1);
+  EXPECT_NEAR(2.828427, moduleStates.frontRight.to<double>(), 0.1);
+  EXPECT_NEAR(2.828427, moduleStates.rearLeft.to<double>(), 0.1);
+  EXPECT_NEAR(-2.828427, moduleStates.rearRight.to<double>(), 0.1);
+}
+
+TEST_F(MecanumDriveKinematicsTest, StrafeForwardKinematics) {
+  MecanumDriveWheelSpeeds wheelSpeeds{-2.828427_mps, 2.828427_mps, 2.828427_mps,
+                                      -2.828427_mps};
+  auto chassisSpeeds = kinematics.ToChassisSpeeds(wheelSpeeds);
+
+  /*
+    By equation (13.13) of the state-space-guide, the chassis motion from wheel
+    velocities: fl 3.535534 fr 3.535534 rl 3.535534 rr 3.535534 will be
+    [[5][0][0]]
+  */
+
+  EXPECT_NEAR(0.0, chassisSpeeds.vx.to<double>(), 0.1);
+  EXPECT_NEAR(4.0, chassisSpeeds.vy.to<double>(), 0.1);
+  EXPECT_NEAR(0.0, chassisSpeeds.omega.to<double>(), 0.1);
+}
+
+TEST_F(MecanumDriveKinematicsTest, RotationInverseKinematics) {
+  ChassisSpeeds speeds{0_mps, 0_mps,
+                       units::radians_per_second_t(2 * wpi::math::pi)};
+  auto moduleStates = kinematics.ToWheelSpeeds(speeds);
+
+  /*
+    By equation (13.12) of the state-space-guide, the wheel speeds should
+    be as follows:
+    velocities: fl -106.629191 fr 106.629191 rl -106.629191 rr 106.629191
+  */
+
+  EXPECT_NEAR(-106.62919, moduleStates.frontLeft.to<double>(), 0.1);
+  EXPECT_NEAR(106.62919, moduleStates.frontRight.to<double>(), 0.1);
+  EXPECT_NEAR(-106.62919, moduleStates.rearLeft.to<double>(), 0.1);
+  EXPECT_NEAR(106.62919, moduleStates.rearRight.to<double>(), 0.1);
+}
+
+TEST_F(MecanumDriveKinematicsTest, RotationForwardKinematics) {
+  MecanumDriveWheelSpeeds wheelSpeeds{-106.62919_mps, 106.62919_mps,
+                                      -106.62919_mps, 106.62919_mps};
+  auto chassisSpeeds = kinematics.ToChassisSpeeds(wheelSpeeds);
+
+  /*
+    By equation (13.13) of the state-space-guide, the chassis motion from wheel
+    velocities: fl -106.629191 fr 106.629191 rl -106.629191 rr 106.629191 should
+    be [[0][0][2pi]]
+  */
+
+  EXPECT_NEAR(0.0, chassisSpeeds.vx.to<double>(), 0.1);
+  EXPECT_NEAR(0.0, chassisSpeeds.vy.to<double>(), 0.1);
+  EXPECT_NEAR(2 * wpi::math::pi, chassisSpeeds.omega.to<double>(), 0.1);
+}
+
+TEST_F(MecanumDriveKinematicsTest, MixedRotationTranslationInverseKinematics) {
+  ChassisSpeeds speeds{2_mps, 3_mps, 1_rad_per_s};
+  auto moduleStates = kinematics.ToWheelSpeeds(speeds);
+
+  /*
+    By equation (13.12) of the state-space-guide, the wheel speeds should
+    be as follows:
+    velocities: fl -17.677670 fr 20.506097 rl -13.435029 rr 16.263456
+  */
+
+  EXPECT_NEAR(-17.677670, moduleStates.frontLeft.to<double>(), 0.1);
+  EXPECT_NEAR(20.506097, moduleStates.frontRight.to<double>(), 0.1);
+  EXPECT_NEAR(-13.435, moduleStates.rearLeft.to<double>(), 0.1);
+  EXPECT_NEAR(16.26, moduleStates.rearRight.to<double>(), 0.1);
+}
+
+TEST_F(MecanumDriveKinematicsTest, MixedRotationTranslationForwardKinematics) {
+  MecanumDriveWheelSpeeds wheelSpeeds{-17.677670_mps, 20.506097_mps,
+                                      -13.435_mps, 16.26_mps};
+
+  auto chassisSpeeds = kinematics.ToChassisSpeeds(wheelSpeeds);
+
+  /*
+    By equation (13.13) of the state-space-guide, the chassis motion from wheel
+    velocities: fl -17.677670 fr 20.506097 rl -13.435029 rr 16.263456 should be
+    [[2][3][1]]
+  */
+
+  EXPECT_NEAR(2.0, chassisSpeeds.vx.to<double>(), 0.1);
+  EXPECT_NEAR(3.0, chassisSpeeds.vy.to<double>(), 0.1);
+  EXPECT_NEAR(1.0, chassisSpeeds.omega.to<double>(), 0.1);
+}
+
+TEST_F(MecanumDriveKinematicsTest, OffCenterRotationInverseKinematics) {
+  ChassisSpeeds speeds{0_mps, 0_mps, 1_rad_per_s};
+  auto moduleStates = kinematics.ToWheelSpeeds(speeds, m_fl);
+
+  /*
+    By equation (13.12) of the state-space-guide, the wheel speeds should
+    be as follows:
+    velocities: fl 0.000000 fr 16.970563 rl -16.970563 rr 33.941125
+  */
+
+  EXPECT_NEAR(0, moduleStates.frontLeft.to<double>(), 0.1);
+  EXPECT_NEAR(16.971, moduleStates.frontRight.to<double>(), 0.1);
+  EXPECT_NEAR(-16.971, moduleStates.rearLeft.to<double>(), 0.1);
+  EXPECT_NEAR(33.941, moduleStates.rearRight.to<double>(), 0.1);
+}
+
+TEST_F(MecanumDriveKinematicsTest, OffCenterRotationForwardKinematics) {
+  MecanumDriveWheelSpeeds wheelSpeeds{0_mps, 16.971_mps, -16.971_mps,
+                                      33.941_mps};
+  auto chassisSpeeds = kinematics.ToChassisSpeeds(wheelSpeeds);
+
+  /*
+    By equation (13.13) of the state-space-guide, the chassis motion from the
+    wheel velocities should be [[12][-12][1]]
+  */
+
+  EXPECT_NEAR(12.0, chassisSpeeds.vx.to<double>(), 0.1);
+  EXPECT_NEAR(-12, chassisSpeeds.vy.to<double>(), 0.1);
+  EXPECT_NEAR(1.0, chassisSpeeds.omega.to<double>(), 0.1);
+}
+
+TEST_F(MecanumDriveKinematicsTest,
+       OffCenterTranslationRotationInverseKinematics) {
+  ChassisSpeeds speeds{5_mps, 2_mps, 1_rad_per_s};
+  auto moduleStates = kinematics.ToWheelSpeeds(speeds, m_fl);
+
+  /*
+    By equation (13.12) of the state-space-guide, the wheel speeds should
+    be as follows:
+    velocities: fl 2.121320 fr 21.920310 rl -12.020815 rr 36.062446
+  */
+  EXPECT_NEAR(2.12, moduleStates.frontLeft.to<double>(), 0.1);
+  EXPECT_NEAR(21.92, moduleStates.frontRight.to<double>(), 0.1);
+  EXPECT_NEAR(-12.02, moduleStates.rearLeft.to<double>(), 0.1);
+  EXPECT_NEAR(36.06, moduleStates.rearRight.to<double>(), 0.1);
+}
+
+TEST_F(MecanumDriveKinematicsTest,
+       OffCenterTranslationRotationForwardKinematics) {
+  MecanumDriveWheelSpeeds wheelSpeeds{2.12_mps, 21.92_mps, -12.02_mps,
+                                      36.06_mps};
+  auto chassisSpeeds = kinematics.ToChassisSpeeds(wheelSpeeds);
+
+  /*
+    By equation (13.13) of the state-space-guide, the chassis motion from the
+    wheel velocities should be [[17][-10][1]]
+  */
+
+  EXPECT_NEAR(17.0, chassisSpeeds.vx.to<double>(), 0.1);
+  EXPECT_NEAR(-10, chassisSpeeds.vy.to<double>(), 0.1);
+  EXPECT_NEAR(1.0, chassisSpeeds.omega.to<double>(), 0.1);
+}
+
+TEST_F(MecanumDriveKinematicsTest, NormalizeTest) {
+  MecanumDriveWheelSpeeds wheelSpeeds{5_mps, 6_mps, 4_mps, 7_mps};
+  wheelSpeeds.Normalize(5.5_mps);
+
+  double kFactor = 5.5 / 7.0;
+
+  EXPECT_NEAR(wheelSpeeds.frontLeft.to<double>(), 5.0 * kFactor, 1E-9);
+  EXPECT_NEAR(wheelSpeeds.frontRight.to<double>(), 6.0 * kFactor, 1E-9);
+  EXPECT_NEAR(wheelSpeeds.rearLeft.to<double>(), 4.0 * kFactor, 1E-9);
+  EXPECT_NEAR(wheelSpeeds.rearRight.to<double>(), 7.0 * kFactor, 1E-9);
+}
diff --git a/wpilibc/src/test/native/cpp/kinematics/MecanumDriveOdometryTest.cpp b/wpilibc/src/test/native/cpp/kinematics/MecanumDriveOdometryTest.cpp
new file mode 100644
index 0000000..5d990bf
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/kinematics/MecanumDriveOdometryTest.cpp
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/kinematics/MecanumDriveOdometry.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class MecanumDriveOdometryTest : public ::testing::Test {
+ protected:
+  Translation2d m_fl{12_m, 12_m};
+  Translation2d m_fr{12_m, -12_m};
+  Translation2d m_bl{-12_m, 12_m};
+  Translation2d m_br{-12_m, -12_m};
+
+  MecanumDriveKinematics kinematics{m_fl, m_fr, m_bl, m_br};
+  MecanumDriveOdometry odometry{kinematics, 0_rad};
+};
+
+TEST_F(MecanumDriveOdometryTest, MultipleConsecutiveUpdates) {
+  odometry.ResetPosition(Pose2d(), 0_rad);
+  MecanumDriveWheelSpeeds wheelSpeeds{3.536_mps, 3.536_mps, 3.536_mps,
+                                      3.536_mps};
+
+  odometry.UpdateWithTime(0_s, Rotation2d(), wheelSpeeds);
+  auto secondPose = odometry.UpdateWithTime(0.0_s, Rotation2d(), wheelSpeeds);
+
+  EXPECT_NEAR(secondPose.Translation().X().to<double>(), 0.0, 0.01);
+  EXPECT_NEAR(secondPose.Translation().Y().to<double>(), 0.0, 0.01);
+  EXPECT_NEAR(secondPose.Rotation().Radians().to<double>(), 0.0, 0.01);
+}
+
+TEST_F(MecanumDriveOdometryTest, TwoIterations) {
+  odometry.ResetPosition(Pose2d(), 0_rad);
+  MecanumDriveWheelSpeeds speeds{3.536_mps, 3.536_mps, 3.536_mps, 3.536_mps};
+
+  odometry.UpdateWithTime(0_s, Rotation2d(), MecanumDriveWheelSpeeds{});
+  auto pose = odometry.UpdateWithTime(0.10_s, Rotation2d(), speeds);
+
+  EXPECT_NEAR(pose.Translation().X().to<double>(), 0.5, 0.01);
+  EXPECT_NEAR(pose.Translation().Y().to<double>(), 0.0, 0.01);
+  EXPECT_NEAR(pose.Rotation().Radians().to<double>(), 0.0, 0.01);
+}
+
+TEST_F(MecanumDriveOdometryTest, Test90DegreeTurn) {
+  odometry.ResetPosition(Pose2d(), 0_rad);
+  MecanumDriveWheelSpeeds speeds{-13.328_mps, 39.986_mps, -13.329_mps,
+                                 39.986_mps};
+  odometry.UpdateWithTime(0_s, Rotation2d(), MecanumDriveWheelSpeeds{});
+  auto pose = odometry.UpdateWithTime(1_s, Rotation2d(90_deg), speeds);
+
+  EXPECT_NEAR(pose.Translation().X().to<double>(), 12, 0.01);
+  EXPECT_NEAR(pose.Translation().Y().to<double>(), 12, 0.01);
+  EXPECT_NEAR(pose.Rotation().Degrees().to<double>(), 90.0, 0.01);
+}
+
+TEST_F(MecanumDriveOdometryTest, GyroAngleReset) {
+  odometry.ResetPosition(Pose2d(), Rotation2d(90_deg));
+
+  MecanumDriveWheelSpeeds speeds{3.536_mps, 3.536_mps, 3.536_mps, 3.536_mps};
+
+  odometry.UpdateWithTime(0_s, Rotation2d(90_deg), MecanumDriveWheelSpeeds{});
+  auto pose = odometry.UpdateWithTime(0.10_s, Rotation2d(90_deg), speeds);
+
+  EXPECT_NEAR(pose.Translation().X().to<double>(), 0.5, 0.01);
+  EXPECT_NEAR(pose.Translation().Y().to<double>(), 0.0, 0.01);
+  EXPECT_NEAR(pose.Rotation().Radians().to<double>(), 0.0, 0.01);
+}
diff --git a/wpilibc/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp b/wpilibc/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp
new file mode 100644
index 0000000..8fd67ea
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp
@@ -0,0 +1,183 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <units/units.h>
+#include <wpi/math>
+
+#include "frc/geometry/Translation2d.h"
+#include "frc/kinematics/SwerveDriveKinematics.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static constexpr double kEpsilon = 0.1;
+
+class SwerveDriveKinematicsTest : public ::testing::Test {
+ protected:
+  Translation2d m_fl{12_m, 12_m};
+  Translation2d m_fr{12_m, -12_m};
+  Translation2d m_bl{-12_m, 12_m};
+  Translation2d m_br{-12_m, -12_m};
+
+  SwerveDriveKinematics<4> m_kinematics{m_fl, m_fr, m_bl, m_br};
+};
+
+TEST_F(SwerveDriveKinematicsTest, StraightLineInverseKinematics) {
+  ChassisSpeeds speeds{5.0_mps, 0.0_mps, 0.0_rad_per_s};
+
+  auto [fl, fr, bl, br] = m_kinematics.ToSwerveModuleStates(speeds);
+
+  EXPECT_NEAR(fl.speed.to<double>(), 5.0, kEpsilon);
+  EXPECT_NEAR(fr.speed.to<double>(), 5.0, kEpsilon);
+  EXPECT_NEAR(bl.speed.to<double>(), 5.0, kEpsilon);
+  EXPECT_NEAR(br.speed.to<double>(), 5.0, kEpsilon);
+
+  EXPECT_NEAR(fl.angle.Radians().to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(fr.angle.Radians().to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(bl.angle.Radians().to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(br.angle.Radians().to<double>(), 0.0, kEpsilon);
+}
+
+TEST_F(SwerveDriveKinematicsTest, StraightLineForwardKinematics) {
+  SwerveModuleState state{5.0_mps, Rotation2d()};
+
+  auto chassisSpeeds = m_kinematics.ToChassisSpeeds(state, state, state, state);
+
+  EXPECT_NEAR(chassisSpeeds.vx.to<double>(), 5.0, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.vy.to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.omega.to<double>(), 0.0, kEpsilon);
+}
+
+TEST_F(SwerveDriveKinematicsTest, StraightStrafeInverseKinematics) {
+  ChassisSpeeds speeds{0_mps, 5_mps, 0_rad_per_s};
+  auto [fl, fr, bl, br] = m_kinematics.ToSwerveModuleStates(speeds);
+
+  EXPECT_NEAR(fl.speed.to<double>(), 5.0, kEpsilon);
+  EXPECT_NEAR(fr.speed.to<double>(), 5.0, kEpsilon);
+  EXPECT_NEAR(bl.speed.to<double>(), 5.0, kEpsilon);
+  EXPECT_NEAR(br.speed.to<double>(), 5.0, kEpsilon);
+
+  EXPECT_NEAR(fl.angle.Degrees().to<double>(), 90.0, kEpsilon);
+  EXPECT_NEAR(fr.angle.Degrees().to<double>(), 90.0, kEpsilon);
+  EXPECT_NEAR(bl.angle.Degrees().to<double>(), 90.0, kEpsilon);
+  EXPECT_NEAR(br.angle.Degrees().to<double>(), 90.0, kEpsilon);
+}
+
+TEST_F(SwerveDriveKinematicsTest, StraightStrafeForwardKinematics) {
+  SwerveModuleState state{5_mps, Rotation2d(90_deg)};
+  auto chassisSpeeds = m_kinematics.ToChassisSpeeds(state, state, state, state);
+
+  EXPECT_NEAR(chassisSpeeds.vx.to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.vy.to<double>(), 5.0, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.omega.to<double>(), 0.0, kEpsilon);
+}
+
+TEST_F(SwerveDriveKinematicsTest, TurnInPlaceInverseKinematics) {
+  ChassisSpeeds speeds{0_mps, 0_mps,
+                       units::radians_per_second_t(2 * wpi::math::pi)};
+  auto [fl, fr, bl, br] = m_kinematics.ToSwerveModuleStates(speeds);
+
+  EXPECT_NEAR(fl.speed.to<double>(), 106.63, kEpsilon);
+  EXPECT_NEAR(fr.speed.to<double>(), 106.63, kEpsilon);
+  EXPECT_NEAR(bl.speed.to<double>(), 106.63, kEpsilon);
+  EXPECT_NEAR(br.speed.to<double>(), 106.63, kEpsilon);
+
+  EXPECT_NEAR(fl.angle.Degrees().to<double>(), 135.0, kEpsilon);
+  EXPECT_NEAR(fr.angle.Degrees().to<double>(), 45.0, kEpsilon);
+  EXPECT_NEAR(bl.angle.Degrees().to<double>(), -135.0, kEpsilon);
+  EXPECT_NEAR(br.angle.Degrees().to<double>(), -45.0, kEpsilon);
+}
+
+TEST_F(SwerveDriveKinematicsTest, TurnInPlaceForwardKinematics) {
+  SwerveModuleState fl{106.629_mps, Rotation2d(135_deg)};
+  SwerveModuleState fr{106.629_mps, Rotation2d(45_deg)};
+  SwerveModuleState bl{106.629_mps, Rotation2d(-135_deg)};
+  SwerveModuleState br{106.629_mps, Rotation2d(-45_deg)};
+
+  auto chassisSpeeds = m_kinematics.ToChassisSpeeds(fl, fr, bl, br);
+
+  EXPECT_NEAR(chassisSpeeds.vx.to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.vy.to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.omega.to<double>(), 2 * wpi::math::pi, kEpsilon);
+}
+
+TEST_F(SwerveDriveKinematicsTest, OffCenterCORRotationInverseKinematics) {
+  ChassisSpeeds speeds{0_mps, 0_mps,
+                       units::radians_per_second_t(2 * wpi::math::pi)};
+  auto [fl, fr, bl, br] = m_kinematics.ToSwerveModuleStates(speeds, m_fl);
+
+  EXPECT_NEAR(fl.speed.to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(fr.speed.to<double>(), 150.796, kEpsilon);
+  EXPECT_NEAR(bl.speed.to<double>(), 150.796, kEpsilon);
+  EXPECT_NEAR(br.speed.to<double>(), 213.258, kEpsilon);
+
+  EXPECT_NEAR(fl.angle.Degrees().to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(fr.angle.Degrees().to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(bl.angle.Degrees().to<double>(), -90.0, kEpsilon);
+  EXPECT_NEAR(br.angle.Degrees().to<double>(), -45.0, kEpsilon);
+}
+
+TEST_F(SwerveDriveKinematicsTest, OffCenterCORRotationForwardKinematics) {
+  SwerveModuleState fl{0.0_mps, Rotation2d(0_deg)};
+  SwerveModuleState fr{150.796_mps, Rotation2d(0_deg)};
+  SwerveModuleState bl{150.796_mps, Rotation2d(-90_deg)};
+  SwerveModuleState br{213.258_mps, Rotation2d(-45_deg)};
+
+  auto chassisSpeeds = m_kinematics.ToChassisSpeeds(fl, fr, bl, br);
+
+  EXPECT_NEAR(chassisSpeeds.vx.to<double>(), 75.398, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.vy.to<double>(), -75.398, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.omega.to<double>(), 2 * wpi::math::pi, kEpsilon);
+}
+
+TEST_F(SwerveDriveKinematicsTest,
+       OffCenterCORRotationAndTranslationInverseKinematics) {
+  ChassisSpeeds speeds{0_mps, 3.0_mps, 1.5_rad_per_s};
+  auto [fl, fr, bl, br] =
+      m_kinematics.ToSwerveModuleStates(speeds, Translation2d(24_m, 0_m));
+
+  EXPECT_NEAR(fl.speed.to<double>(), 23.43, kEpsilon);
+  EXPECT_NEAR(fr.speed.to<double>(), 23.43, kEpsilon);
+  EXPECT_NEAR(bl.speed.to<double>(), 54.08, kEpsilon);
+  EXPECT_NEAR(br.speed.to<double>(), 54.08, kEpsilon);
+
+  EXPECT_NEAR(fl.angle.Degrees().to<double>(), -140.19, kEpsilon);
+  EXPECT_NEAR(fr.angle.Degrees().to<double>(), -39.81, kEpsilon);
+  EXPECT_NEAR(bl.angle.Degrees().to<double>(), -109.44, kEpsilon);
+  EXPECT_NEAR(br.angle.Degrees().to<double>(), -70.56, kEpsilon);
+}
+
+TEST_F(SwerveDriveKinematicsTest,
+       OffCenterCORRotationAndTranslationForwardKinematics) {
+  SwerveModuleState fl{23.43_mps, Rotation2d(-140.19_deg)};
+  SwerveModuleState fr{23.43_mps, Rotation2d(-39.81_deg)};
+  SwerveModuleState bl{54.08_mps, Rotation2d(-109.44_deg)};
+  SwerveModuleState br{54.08_mps, Rotation2d(-70.56_deg)};
+
+  auto chassisSpeeds = m_kinematics.ToChassisSpeeds(fl, fr, bl, br);
+
+  EXPECT_NEAR(chassisSpeeds.vx.to<double>(), 0.0, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.vy.to<double>(), -33.0, kEpsilon);
+  EXPECT_NEAR(chassisSpeeds.omega.to<double>(), 1.5, kEpsilon);
+}
+
+TEST_F(SwerveDriveKinematicsTest, NormalizeTest) {
+  SwerveModuleState state1{5.0_mps, Rotation2d()};
+  SwerveModuleState state2{6.0_mps, Rotation2d()};
+  SwerveModuleState state3{4.0_mps, Rotation2d()};
+  SwerveModuleState state4{7.0_mps, Rotation2d()};
+
+  std::array<SwerveModuleState, 4> arr{state1, state2, state3, state4};
+  SwerveDriveKinematics<4>::NormalizeWheelSpeeds(&arr, 5.5_mps);
+
+  double kFactor = 5.5 / 7.0;
+
+  EXPECT_NEAR(arr[0].speed.to<double>(), 5.0 * kFactor, kEpsilon);
+  EXPECT_NEAR(arr[1].speed.to<double>(), 6.0 * kFactor, kEpsilon);
+  EXPECT_NEAR(arr[2].speed.to<double>(), 4.0 * kFactor, kEpsilon);
+  EXPECT_NEAR(arr[3].speed.to<double>(), 7.0 * kFactor, kEpsilon);
+}
diff --git a/wpilibc/src/test/native/cpp/kinematics/SwerveDriveOdometryTest.cpp b/wpilibc/src/test/native/cpp/kinematics/SwerveDriveOdometryTest.cpp
new file mode 100644
index 0000000..d0399dc
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/kinematics/SwerveDriveOdometryTest.cpp
@@ -0,0 +1,74 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/kinematics/SwerveDriveKinematics.h"
+#include "frc/kinematics/SwerveDriveOdometry.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static constexpr double kEpsilon = 0.01;
+
+class SwerveDriveOdometryTest : public ::testing::Test {
+ protected:
+  Translation2d m_fl{12_m, 12_m};
+  Translation2d m_fr{12_m, -12_m};
+  Translation2d m_bl{-12_m, 12_m};
+  Translation2d m_br{-12_m, -12_m};
+
+  SwerveDriveKinematics<4> m_kinematics{m_fl, m_fr, m_bl, m_br};
+  SwerveDriveOdometry<4> m_odometry{m_kinematics, 0_rad};
+};
+
+TEST_F(SwerveDriveOdometryTest, TwoIterations) {
+  SwerveModuleState state{5_mps, Rotation2d()};
+
+  m_odometry.ResetPosition(Pose2d(), 0_rad);
+  m_odometry.UpdateWithTime(0_s, Rotation2d(), SwerveModuleState(),
+                            SwerveModuleState(), SwerveModuleState(),
+                            SwerveModuleState());
+  auto pose = m_odometry.UpdateWithTime(0.1_s, Rotation2d(), state, state,
+                                        state, state);
+
+  EXPECT_NEAR(0.5, pose.Translation().X().to<double>(), kEpsilon);
+  EXPECT_NEAR(0.0, pose.Translation().Y().to<double>(), kEpsilon);
+  EXPECT_NEAR(0.0, pose.Rotation().Degrees().to<double>(), kEpsilon);
+}
+
+TEST_F(SwerveDriveOdometryTest, 90DegreeTurn) {
+  SwerveModuleState fl{18.85_mps, Rotation2d(90_deg)};
+  SwerveModuleState fr{42.15_mps, Rotation2d(26.565_deg)};
+  SwerveModuleState bl{18.85_mps, Rotation2d(-90_deg)};
+  SwerveModuleState br{42.15_mps, Rotation2d(-26.565_deg)};
+
+  SwerveModuleState zero{0_mps, Rotation2d()};
+
+  m_odometry.ResetPosition(Pose2d(), 0_rad);
+  m_odometry.UpdateWithTime(0_s, Rotation2d(), zero, zero, zero, zero);
+  auto pose =
+      m_odometry.UpdateWithTime(1_s, Rotation2d(90_deg), fl, fr, bl, br);
+
+  EXPECT_NEAR(12.0, pose.Translation().X().to<double>(), kEpsilon);
+  EXPECT_NEAR(12.0, pose.Translation().Y().to<double>(), kEpsilon);
+  EXPECT_NEAR(90.0, pose.Rotation().Degrees().to<double>(), kEpsilon);
+}
+
+TEST_F(SwerveDriveOdometryTest, GyroAngleReset) {
+  m_odometry.ResetPosition(Pose2d(), Rotation2d(90_deg));
+
+  SwerveModuleState state{5_mps, Rotation2d()};
+
+  m_odometry.UpdateWithTime(0_s, Rotation2d(90_deg), SwerveModuleState(),
+                            SwerveModuleState(), SwerveModuleState(),
+                            SwerveModuleState());
+  auto pose = m_odometry.UpdateWithTime(0.1_s, Rotation2d(90_deg), state, state,
+                                        state, state);
+
+  EXPECT_NEAR(0.5, pose.Translation().X().to<double>(), kEpsilon);
+  EXPECT_NEAR(0.0, pose.Translation().Y().to<double>(), kEpsilon);
+  EXPECT_NEAR(0.0, pose.Rotation().Degrees().to<double>(), kEpsilon);
+}
diff --git a/wpilibc/src/test/native/cpp/main.cpp b/wpilibc/src/test/native/cpp/main.cpp
new file mode 100644
index 0000000..c6b6c58
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/main.cpp
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <hal/HALBase.h>
+
+#include "gtest/gtest.h"
+
+int main(int argc, char** argv) {
+  HAL_Initialize(500, 0);
+  ::testing::InitGoogleTest(&argc, argv);
+  int ret = RUN_ALL_TESTS();
+  return ret;
+}
diff --git a/wpilibc/src/test/native/cpp/shuffleboard/MockActuatorSendable.cpp b/wpilibc/src/test/native/cpp/shuffleboard/MockActuatorSendable.cpp
new file mode 100644
index 0000000..172d7c6
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/shuffleboard/MockActuatorSendable.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "shuffleboard/MockActuatorSendable.h"
+
+#include "frc/smartdashboard/SendableRegistry.h"
+
+using namespace frc;
+
+MockActuatorSendable::MockActuatorSendable(wpi::StringRef name) {
+  SendableRegistry::GetInstance().Add(this, name);
+}
+
+void MockActuatorSendable::InitSendable(SendableBuilder& builder) {
+  builder.SetActuator(true);
+}
diff --git a/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp b/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp
new file mode 100644
index 0000000..ae21526
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp
@@ -0,0 +1,105 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/ShuffleboardInstance.h"  // NOLINT(build/include_order)
+
+#include <memory>
+#include <string>
+
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableInstance.h>
+
+#include "frc/shuffleboard/ShuffleboardInstance.h"
+#include "gtest/gtest.h"
+#include "shuffleboard/MockActuatorSendable.h"
+
+using namespace frc;
+
+class ShuffleboardInstanceTest : public testing::Test {
+  void SetUp() override {
+    m_ntInstance = nt::NetworkTableInstance::Create();
+    m_shuffleboardInstance =
+        std::make_unique<detail::ShuffleboardInstance>(m_ntInstance);
+  }
+
+ protected:
+  nt::NetworkTableInstance m_ntInstance;
+  std::unique_ptr<detail::ShuffleboardInstance> m_shuffleboardInstance;
+};
+
+TEST_F(ShuffleboardInstanceTest, PathFluent) {
+  auto entry = m_shuffleboardInstance->GetTab("Tab Title")
+                   .GetLayout("List Layout", "List")
+                   .Add("Data", "string")
+                   .WithWidget("Text View")
+                   .GetEntry();
+
+  EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value";
+  EXPECT_EQ("/Shuffleboard/Tab Title/List Layout/Data", entry.GetName())
+      << "Entry path generated incorrectly";
+}
+
+TEST_F(ShuffleboardInstanceTest, NestedLayoutsFluent) {
+  auto entry = m_shuffleboardInstance->GetTab("Tab")
+                   .GetLayout("First", "List")
+                   .GetLayout("Second", "List")
+                   .GetLayout("Third", "List")
+                   .GetLayout("Fourth", "List")
+                   .Add("Value", "string")
+                   .GetEntry();
+
+  EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value";
+  EXPECT_EQ("/Shuffleboard/Tab/First/Second/Third/Fourth/Value",
+            entry.GetName())
+      << "Entry path generated incorrectly";
+}
+
+TEST_F(ShuffleboardInstanceTest, NestedLayoutsOop) {
+  ShuffleboardTab& tab = m_shuffleboardInstance->GetTab("Tab");
+  ShuffleboardLayout& first = tab.GetLayout("First", "List");
+  ShuffleboardLayout& second = first.GetLayout("Second", "List");
+  ShuffleboardLayout& third = second.GetLayout("Third", "List");
+  ShuffleboardLayout& fourth = third.GetLayout("Fourth", "List");
+  SimpleWidget& widget = fourth.Add("Value", "string");
+  auto entry = widget.GetEntry();
+
+  EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value";
+  EXPECT_EQ("/Shuffleboard/Tab/First/Second/Third/Fourth/Value",
+            entry.GetName())
+      << "Entry path generated incorrectly";
+}
+
+TEST_F(ShuffleboardInstanceTest, LayoutTypeIsSet) {
+  std::string layoutType = "Type";
+  m_shuffleboardInstance->GetTab("Tab").GetLayout("Title", layoutType);
+  m_shuffleboardInstance->Update();
+  nt::NetworkTableEntry entry = m_ntInstance.GetEntry(
+      "/Shuffleboard/.metadata/Tab/Title/PreferredComponent");
+  EXPECT_EQ(layoutType, entry.GetString("Not Set")) << "Layout type not set";
+}
+
+TEST_F(ShuffleboardInstanceTest, NestedActuatorWidgetsAreDisabled) {
+  MockActuatorSendable sendable("Actuator");
+  m_shuffleboardInstance->GetTab("Tab")
+      .GetLayout("Title", "Type")
+      .Add(sendable);
+  auto controllableEntry =
+      m_ntInstance.GetEntry("/Shuffleboard/Tab/Title/Actuator/.controllable");
+  m_shuffleboardInstance->Update();
+
+  // Note: we use the unsafe `GetBoolean()` method because if the value is NOT
+  // a boolean, or if it is not present, then something has clearly gone very,
+  // very wrong
+  bool controllable = controllableEntry.GetValue()->GetBoolean();
+  // Sanity check
+  EXPECT_TRUE(controllable)
+      << "The nested actuator widget should be enabled by default";
+  m_shuffleboardInstance->DisableActuatorWidgets();
+  controllable = controllableEntry.GetValue()->GetBoolean();
+  EXPECT_FALSE(controllable)
+      << "The nested actuator widget should have been disabled";
+}
diff --git a/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardTest.cpp b/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardTest.cpp
new file mode 100644
index 0000000..d39d59d
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardTest.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/shuffleboard/Shuffleboard.h"
+#include "frc/shuffleboard/ShuffleboardTab.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class ShuffleboardTest : public testing::Test {};
+
+TEST_F(ShuffleboardTest, TabObjectsCached) {
+  ShuffleboardTab& tab1 = Shuffleboard::GetTab("testTabObjectsCached");
+  ShuffleboardTab& tab2 = Shuffleboard::GetTab("testTabObjectsCached");
+  EXPECT_EQ(&tab1, &tab2) << "Tab objects were not cached";
+}
diff --git a/wpilibc/src/test/native/cpp/shuffleboard/SuppliedValueWidgetTest.cpp b/wpilibc/src/test/native/cpp/shuffleboard/SuppliedValueWidgetTest.cpp
new file mode 100644
index 0000000..8e39915
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/shuffleboard/SuppliedValueWidgetTest.cpp
@@ -0,0 +1,107 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableInstance.h>
+
+#include "frc/shuffleboard/ShuffleboardInstance.h"
+#include "frc/shuffleboard/ShuffleboardTab.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class SuppliedValueWidgetTest : public testing::Test {
+  void SetUp() override {
+    m_ntInstance = nt::NetworkTableInstance::Create();
+    m_instance = std::make_unique<detail::ShuffleboardInstance>(m_ntInstance);
+    m_tab = &(m_instance->GetTab("Tab"));
+  }
+
+ protected:
+  nt::NetworkTableInstance m_ntInstance;
+  ShuffleboardTab* m_tab;
+  std::unique_ptr<detail::ShuffleboardInstance> m_instance;
+};
+
+TEST_F(SuppliedValueWidgetTest, AddString) {
+  std::string str = "foo";
+  m_tab->AddString("String", [&str]() { return str; });
+  auto entry = m_ntInstance.GetEntry("/Shuffleboard/Tab/String");
+
+  m_instance->Update();
+  EXPECT_EQ("foo", entry.GetValue()->GetString());
+}
+
+TEST_F(SuppliedValueWidgetTest, AddNumber) {
+  int num = 0;
+  m_tab->AddNumber("Num", [&num]() { return ++num; });
+  auto entry = m_ntInstance.GetEntry("/Shuffleboard/Tab/Num");
+
+  m_instance->Update();
+  EXPECT_FLOAT_EQ(1.0, entry.GetValue()->GetDouble());
+}
+
+TEST_F(SuppliedValueWidgetTest, AddBoolean) {
+  bool value = true;
+  m_tab->AddBoolean("Bool", [&value]() { return value; });
+  auto entry = m_ntInstance.GetEntry("/Shuffleboard/Tab/Bool");
+
+  m_instance->Update();
+  EXPECT_EQ(true, entry.GetValue()->GetBoolean());
+}
+
+TEST_F(SuppliedValueWidgetTest, AddStringArray) {
+  std::vector<std::string> strings = {"foo", "bar"};
+  m_tab->AddStringArray("Strings", [&strings]() { return strings; });
+  auto entry = m_ntInstance.GetEntry("/Shuffleboard/Tab/Strings");
+
+  m_instance->Update();
+  auto actual = entry.GetValue()->GetStringArray();
+
+  EXPECT_EQ(strings.size(), actual.size());
+  for (size_t i = 0; i < strings.size(); i++) {
+    EXPECT_EQ(strings[i], actual[i]);
+  }
+}
+
+TEST_F(SuppliedValueWidgetTest, AddNumberArray) {
+  std::vector<double> nums = {0, 1, 2, 3};
+  m_tab->AddNumberArray("Numbers", [&nums]() { return nums; });
+  auto entry = m_ntInstance.GetEntry("/Shuffleboard/Tab/Numbers");
+
+  m_instance->Update();
+  auto actual = entry.GetValue()->GetDoubleArray();
+
+  EXPECT_EQ(nums.size(), actual.size());
+  for (size_t i = 0; i < nums.size(); i++) {
+    EXPECT_FLOAT_EQ(nums[i], actual[i]);
+  }
+}
+
+TEST_F(SuppliedValueWidgetTest, AddBooleanArray) {
+  std::vector<int> bools = {true, false};
+  m_tab->AddBooleanArray("Booleans", [&bools]() { return bools; });
+  auto entry = m_ntInstance.GetEntry("/Shuffleboard/Tab/Booleans");
+
+  m_instance->Update();
+  auto actual = entry.GetValue()->GetBooleanArray();
+
+  EXPECT_EQ(bools.size(), actual.size());
+  for (size_t i = 0; i < bools.size(); i++) {
+    EXPECT_FLOAT_EQ(bools[i], actual[i]);
+  }
+}
+
+TEST_F(SuppliedValueWidgetTest, AddRaw) {
+  wpi::StringRef bytes = "\1\2\3";
+  m_tab->AddRaw("Raw", [&bytes]() { return bytes; });
+  auto entry = m_ntInstance.GetEntry("/Shuffleboard/Tab/Raw");
+
+  m_instance->Update();
+  auto actual = entry.GetValue()->GetRaw();
+  EXPECT_EQ(bytes, actual);
+}
diff --git a/wpilibc/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp b/wpilibc/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp
new file mode 100644
index 0000000..f2f0a38
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp
@@ -0,0 +1,133 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019-2020 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <chrono>
+#include <iostream>
+#include <vector>
+
+#include <units/units.h>
+
+#include "frc/geometry/Pose2d.h"
+#include "frc/geometry/Rotation2d.h"
+#include "frc/spline/QuinticHermiteSpline.h"
+#include "frc/spline/SplineHelper.h"
+#include "frc/spline/SplineParameterizer.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+namespace frc {
+class CubicHermiteSplineTest : public ::testing::Test {
+ protected:
+  static void Run(const Pose2d& a, const std::vector<Translation2d>& waypoints,
+                  const Pose2d& b) {
+    // Start the timer.
+    const auto start = std::chrono::high_resolution_clock::now();
+
+    // Generate and parameterize the spline.
+
+    const auto [startCV, endCV] =
+        SplineHelper::CubicControlVectorsFromWaypoints(a, waypoints, b);
+
+    const auto splines =
+        SplineHelper::CubicSplinesFromControlVectors(startCV, waypoints, endCV);
+    std::vector<Spline<3>::PoseWithCurvature> poses;
+
+    poses.push_back(splines[0].GetPoint(0.0));
+
+    for (auto&& spline : splines) {
+      auto x = SplineParameterizer::Parameterize(spline);
+      poses.insert(std::end(poses), std::begin(x) + 1, std::end(x));
+    }
+
+    // End timer.
+    const auto finish = std::chrono::high_resolution_clock::now();
+
+    // Calculate the duration (used when benchmarking)
+    const auto duration =
+        std::chrono::duration_cast<std::chrono::microseconds>(finish - start);
+
+    for (unsigned int i = 0; i < poses.size() - 1; i++) {
+      auto& p0 = poses[i];
+      auto& p1 = poses[i + 1];
+
+      // Make sure the twist is under the tolerance defined by the Spline class.
+      auto twist = p0.first.Log(p1.first);
+      EXPECT_LT(std::abs(twist.dx.to<double>()),
+                SplineParameterizer::kMaxDx.to<double>());
+      EXPECT_LT(std::abs(twist.dy.to<double>()),
+                SplineParameterizer::kMaxDy.to<double>());
+      EXPECT_LT(std::abs(twist.dtheta.to<double>()),
+                SplineParameterizer::kMaxDtheta.to<double>());
+    }
+
+    // Check first point.
+    EXPECT_NEAR(poses.front().first.Translation().X().to<double>(),
+                a.Translation().X().to<double>(), 1E-9);
+    EXPECT_NEAR(poses.front().first.Translation().Y().to<double>(),
+                a.Translation().Y().to<double>(), 1E-9);
+    EXPECT_NEAR(poses.front().first.Rotation().Radians().to<double>(),
+                a.Rotation().Radians().to<double>(), 1E-9);
+
+    // Check interior waypoints
+    bool interiorsGood = true;
+    for (auto& waypoint : waypoints) {
+      bool found = false;
+      for (auto& state : poses) {
+        if (std::abs(
+                waypoint.Distance(state.first.Translation()).to<double>()) <
+            1E-9) {
+          found = true;
+        }
+      }
+      interiorsGood &= found;
+    }
+
+    EXPECT_TRUE(interiorsGood);
+
+    // Check last point.
+    EXPECT_NEAR(poses.back().first.Translation().X().to<double>(),
+                b.Translation().X().to<double>(), 1E-9);
+    EXPECT_NEAR(poses.back().first.Translation().Y().to<double>(),
+                b.Translation().Y().to<double>(), 1E-9);
+    EXPECT_NEAR(poses.back().first.Rotation().Radians().to<double>(),
+                b.Rotation().Radians().to<double>(), 1E-9);
+
+    static_cast<void>(duration);
+  }
+};
+}  // namespace frc
+
+TEST_F(CubicHermiteSplineTest, StraightLine) {
+  Run(Pose2d(), std::vector<Translation2d>(), Pose2d(3_m, 0_m, Rotation2d()));
+}
+
+TEST_F(CubicHermiteSplineTest, SCurve) {
+  Pose2d start{0_m, 0_m, Rotation2d(90_deg)};
+  std::vector<Translation2d> waypoints{Translation2d(1_m, 1_m),
+                                       Translation2d(2_m, -1_m)};
+  Pose2d end{3_m, 0_m, Rotation2d{90_deg}};
+  Run(start, waypoints, end);
+}
+
+TEST_F(CubicHermiteSplineTest, OneInterior) {
+  Pose2d start{0_m, 0_m, 0_rad};
+  std::vector<Translation2d> waypoints{Translation2d(2_m, 0_m)};
+  Pose2d end{4_m, 0_m, 0_rad};
+  Run(start, waypoints, end);
+}
+
+TEST_F(CubicHermiteSplineTest, ThrowsOnMalformed) {
+  EXPECT_THROW(
+      Run(Pose2d{0_m, 0_m, Rotation2d(0_deg)}, std::vector<Translation2d>{},
+          Pose2d{1_m, 0_m, Rotation2d(180_deg)}),
+      SplineParameterizer::MalformedSplineException);
+  EXPECT_THROW(
+      Run(Pose2d{10_m, 10_m, Rotation2d(90_deg)}, std::vector<Translation2d>{},
+          Pose2d{10_m, 11_m, Rotation2d(-90_deg)}),
+      SplineParameterizer::MalformedSplineException);
+}
diff --git a/wpilibc/src/test/native/cpp/spline/QuinticHermiteSplineTest.cpp b/wpilibc/src/test/native/cpp/spline/QuinticHermiteSplineTest.cpp
new file mode 100644
index 0000000..8a87053
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/spline/QuinticHermiteSplineTest.cpp
@@ -0,0 +1,96 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019-2020 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <chrono>
+#include <iostream>
+
+#include <units/units.h>
+
+#include "frc/geometry/Pose2d.h"
+#include "frc/geometry/Rotation2d.h"
+#include "frc/spline/QuinticHermiteSpline.h"
+#include "frc/spline/SplineHelper.h"
+#include "frc/spline/SplineParameterizer.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+namespace frc {
+class QuinticHermiteSplineTest : public ::testing::Test {
+ protected:
+  static void Run(const Pose2d& a, const Pose2d& b) {
+    // Start the timer.
+    const auto start = std::chrono::high_resolution_clock::now();
+
+    // Generate and parameterize the spline.
+    const auto spline = SplineHelper::QuinticSplinesFromControlVectors(
+        SplineHelper::QuinticControlVectorsFromWaypoints({a, b}))[0];
+    const auto poses = SplineParameterizer::Parameterize(spline);
+
+    // End timer.
+    const auto finish = std::chrono::high_resolution_clock::now();
+
+    // Calculate the duration (used when benchmarking)
+    const auto duration =
+        std::chrono::duration_cast<std::chrono::microseconds>(finish - start);
+
+    for (unsigned int i = 0; i < poses.size() - 1; i++) {
+      auto& p0 = poses[i];
+      auto& p1 = poses[i + 1];
+
+      // Make sure the twist is under the tolerance defined by the Spline class.
+      auto twist = p0.first.Log(p1.first);
+      EXPECT_LT(std::abs(twist.dx.to<double>()),
+                SplineParameterizer::kMaxDx.to<double>());
+      EXPECT_LT(std::abs(twist.dy.to<double>()),
+                SplineParameterizer::kMaxDy.to<double>());
+      EXPECT_LT(std::abs(twist.dtheta.to<double>()),
+                SplineParameterizer::kMaxDtheta.to<double>());
+    }
+
+    // Check first point.
+    EXPECT_NEAR(poses.front().first.Translation().X().to<double>(),
+                a.Translation().X().to<double>(), 1E-9);
+    EXPECT_NEAR(poses.front().first.Translation().Y().to<double>(),
+                a.Translation().Y().to<double>(), 1E-9);
+    EXPECT_NEAR(poses.front().first.Rotation().Radians().to<double>(),
+                a.Rotation().Radians().to<double>(), 1E-9);
+
+    // Check last point.
+    EXPECT_NEAR(poses.back().first.Translation().X().to<double>(),
+                b.Translation().X().to<double>(), 1E-9);
+    EXPECT_NEAR(poses.back().first.Translation().Y().to<double>(),
+                b.Translation().Y().to<double>(), 1E-9);
+    EXPECT_NEAR(poses.back().first.Rotation().Radians().to<double>(),
+                b.Rotation().Radians().to<double>(), 1E-9);
+
+    static_cast<void>(duration);
+  }
+};
+}  // namespace frc
+
+TEST_F(QuinticHermiteSplineTest, StraightLine) {
+  Run(Pose2d(), Pose2d(3_m, 0_m, Rotation2d()));
+}
+
+TEST_F(QuinticHermiteSplineTest, SimpleSCurve) {
+  Run(Pose2d(), Pose2d(1_m, 1_m, Rotation2d()));
+}
+
+TEST_F(QuinticHermiteSplineTest, SquigglyCurve) {
+  Run(Pose2d(0_m, 0_m, Rotation2d(90_deg)),
+      Pose2d(-1_m, 0_m, Rotation2d(90_deg)));
+}
+
+TEST_F(QuinticHermiteSplineTest, ThrowsOnMalformed) {
+  EXPECT_THROW(Run(Pose2d(0_m, 0_m, Rotation2d(0_deg)),
+                   Pose2d(1_m, 0_m, Rotation2d(180_deg))),
+               SplineParameterizer::MalformedSplineException);
+  EXPECT_THROW(Run(Pose2d(10_m, 10_m, Rotation2d(90_deg)),
+                   Pose2d(10_m, 11_m, Rotation2d(-90_deg))),
+               SplineParameterizer::MalformedSplineException);
+}
diff --git a/wpilibc/src/test/native/cpp/trajectory/CentripetalAccelerationConstraintTest.cpp b/wpilibc/src/test/native/cpp/trajectory/CentripetalAccelerationConstraintTest.cpp
new file mode 100644
index 0000000..37f471a
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/trajectory/CentripetalAccelerationConstraintTest.cpp
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <memory>
+#include <vector>
+
+#include <units/units.h>
+
+#include "frc/trajectory/constraint/CentripetalAccelerationConstraint.h"
+#include "frc/trajectory/constraint/TrajectoryConstraint.h"
+#include "gtest/gtest.h"
+#include "trajectory/TestTrajectory.h"
+
+using namespace frc;
+
+TEST(CentripetalAccelerationConstraintTest, Constraint) {
+  const auto maxCentripetalAcceleration = 7_fps_sq;
+
+  auto config = TrajectoryConfig(12_fps, 12_fps_sq);
+  config.AddConstraint(
+      CentripetalAccelerationConstraint(maxCentripetalAcceleration));
+
+  auto trajectory = TestTrajectory::GetTrajectory(config);
+
+  units::second_t time = 0_s;
+  units::second_t dt = 20_ms;
+  units::second_t duration = trajectory.TotalTime();
+
+  while (time < duration) {
+    const Trajectory::State point = trajectory.Sample(time);
+    time += dt;
+
+    auto centripetalAcceleration =
+        units::math::pow<2>(point.velocity) * point.curvature / 1_rad;
+
+    EXPECT_TRUE(centripetalAcceleration <
+                maxCentripetalAcceleration + 0.05_mps_sq);
+  }
+}
diff --git a/wpilibc/src/test/native/cpp/trajectory/DifferentialDriveKinematicsTest.cpp b/wpilibc/src/test/native/cpp/trajectory/DifferentialDriveKinematicsTest.cpp
new file mode 100644
index 0000000..df5ddbd
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/trajectory/DifferentialDriveKinematicsTest.cpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <memory>
+#include <vector>
+
+#include <units/units.h>
+
+#include "frc/kinematics/DifferentialDriveKinematics.h"
+#include "frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h"
+#include "gtest/gtest.h"
+#include "trajectory/TestTrajectory.h"
+
+using namespace frc;
+
+TEST(DifferentialDriveKinematicsConstraintTest, Constraint) {
+  const auto maxVelocity = 12_fps;
+  const DifferentialDriveKinematics kinematics{27_in};
+
+  auto config = TrajectoryConfig(12_fps, 12_fps_sq);
+  config.AddConstraint(
+      DifferentialDriveKinematicsConstraint(kinematics, maxVelocity));
+
+  auto trajectory = TestTrajectory::GetTrajectory(config);
+
+  units::second_t time = 0_s;
+  units::second_t dt = 20_ms;
+  units::second_t duration = trajectory.TotalTime();
+
+  while (time < duration) {
+    const Trajectory::State point = trajectory.Sample(time);
+    time += dt;
+
+    const ChassisSpeeds chassisSpeeds{point.velocity, 0_mps,
+                                      point.velocity * point.curvature};
+
+    auto [left, right] = kinematics.ToWheelSpeeds(chassisSpeeds);
+
+    EXPECT_TRUE(left < maxVelocity + 0.05_mps);
+    EXPECT_TRUE(right < maxVelocity + 0.05_mps);
+  }
+}
diff --git a/wpilibc/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp b/wpilibc/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp
new file mode 100644
index 0000000..eb230da
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <iostream>
+#include <memory>
+#include <vector>
+
+#include <units/units.h>
+
+#include "frc/kinematics/DifferentialDriveKinematics.h"
+#include "frc/trajectory/constraint/DifferentialDriveVoltageConstraint.h"
+#include "gtest/gtest.h"
+#include "trajectory/TestTrajectory.h"
+
+using namespace frc;
+
+TEST(DifferentialDriveVoltageConstraintTest, Constraint) {
+  // Pick an unreasonably large kA to ensure the constraint has to do some work
+  SimpleMotorFeedforward<units::meter> feedforward{1_V, 1_V / 1_mps,
+                                                   3_V / 1_mps_sq};
+  const DifferentialDriveKinematics kinematics{0.5_m};
+  const auto maxVoltage = 10_V;
+
+  auto config = TrajectoryConfig(12_fps, 12_fps_sq);
+  config.AddConstraint(
+      DifferentialDriveVoltageConstraint(feedforward, kinematics, maxVoltage));
+
+  auto trajectory = TestTrajectory::GetTrajectory(config);
+
+  units::second_t time = 0_s;
+  units::second_t dt = 20_ms;
+  units::second_t duration = trajectory.TotalTime();
+
+  while (time < duration) {
+    const Trajectory::State point = trajectory.Sample(time);
+    time += dt;
+
+    const ChassisSpeeds chassisSpeeds{point.velocity, 0_mps,
+                                      point.velocity * point.curvature};
+
+    auto [left, right] = kinematics.ToWheelSpeeds(chassisSpeeds);
+
+    // Not really a strictly-correct test as we're using the chassis accel
+    // instead of the wheel accel, but much easier than doing it "properly" and
+    // a reasonable check anyway
+    EXPECT_TRUE(feedforward.Calculate(left, point.acceleration) <
+                maxVoltage + 0.05_V);
+    EXPECT_TRUE(feedforward.Calculate(left, point.acceleration) >
+                -maxVoltage - 0.05_V);
+    EXPECT_TRUE(feedforward.Calculate(right, point.acceleration) <
+                maxVoltage + 0.05_V);
+    EXPECT_TRUE(feedforward.Calculate(right, point.acceleration) >
+                -maxVoltage - 0.05_V);
+  }
+}
diff --git a/wpilibc/src/test/native/cpp/trajectory/TrajectoryGeneratorTest.cpp b/wpilibc/src/test/native/cpp/trajectory/TrajectoryGeneratorTest.cpp
new file mode 100644
index 0000000..90046c5
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/trajectory/TrajectoryGeneratorTest.cpp
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019-2020 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <vector>
+
+#include "frc/trajectory/Trajectory.h"
+#include "frc/trajectory/TrajectoryGenerator.h"
+#include "frc/trajectory/constraint/CentripetalAccelerationConstraint.h"
+#include "frc/trajectory/constraint/TrajectoryConstraint.h"
+#include "gtest/gtest.h"
+#include "trajectory/TestTrajectory.h"
+
+using namespace frc;
+
+TEST(TrajectoryGenerationTest, ObeysConstraints) {
+  TrajectoryConfig config{12_fps, 12_fps_sq};
+  auto trajectory = TestTrajectory::GetTrajectory(config);
+
+  units::second_t time = 0_s;
+  units::second_t dt = 20_ms;
+  units::second_t duration = trajectory.TotalTime();
+
+  while (time < duration) {
+    const Trajectory::State point = trajectory.Sample(time);
+    time += dt;
+
+    EXPECT_TRUE(units::math::abs(point.velocity) <= 12_fps + 0.01_fps);
+    EXPECT_TRUE(units::math::abs(point.acceleration) <=
+                12_fps_sq + 0.01_fps_sq);
+  }
+}
+
+TEST(TrajectoryGenertionTest, ReturnsEmptyOnMalformed) {
+  const auto t = TrajectoryGenerator::GenerateTrajectory(
+      std::vector<Pose2d>{Pose2d(0_m, 0_m, Rotation2d(0_deg)),
+                          Pose2d(1_m, 0_m, Rotation2d(180_deg))},
+      TrajectoryConfig(12_fps, 12_fps_sq));
+
+  ASSERT_EQ(t.States().size(), 1u);
+  ASSERT_EQ(t.TotalTime(), 0_s);
+}
diff --git a/wpilibc/src/test/native/cpp/trajectory/TrajectoryJsonTest.cpp b/wpilibc/src/test/native/cpp/trajectory/TrajectoryJsonTest.cpp
new file mode 100644
index 0000000..999d2bb
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/trajectory/TrajectoryJsonTest.cpp
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/trajectory/TrajectoryConfig.h"
+#include "frc/trajectory/TrajectoryUtil.h"
+#include "gtest/gtest.h"
+#include "trajectory/TestTrajectory.h"
+
+using namespace frc;
+
+TEST(TrajectoryJsonTest, DeserializeMatches) {
+  TrajectoryConfig config{12_fps, 12_fps_sq};
+  auto trajectory = TestTrajectory::GetTrajectory(config);
+
+  Trajectory deserialized;
+  EXPECT_NO_THROW(deserialized = TrajectoryUtil::DeserializeTrajectory(
+                      TrajectoryUtil::SerializeTrajectory(trajectory)));
+  EXPECT_EQ(trajectory.States(), deserialized.States());
+}
diff --git a/wpilibc/src/test/native/cpp/trajectory/TrajectoryTransformTest.cpp b/wpilibc/src/test/native/cpp/trajectory/TrajectoryTransformTest.cpp
new file mode 100644
index 0000000..af69b58
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/trajectory/TrajectoryTransformTest.cpp
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <vector>
+
+#include "frc/trajectory/Trajectory.h"
+#include "frc/trajectory/TrajectoryConfig.h"
+#include "frc/trajectory/TrajectoryGenerator.h"
+#include "gtest/gtest.h"
+
+void TestSameShapedTrajectory(std::vector<frc::Trajectory::State> statesA,
+                              std::vector<frc::Trajectory::State> statesB) {
+  for (unsigned int i = 0; i < statesA.size() - 1; i++) {
+    auto a1 = statesA[i].pose;
+    auto a2 = statesA[i + 1].pose;
+
+    auto b1 = statesB[i].pose;
+    auto b2 = statesB[i + 1].pose;
+
+    auto a = a2.RelativeTo(a1);
+    auto b = b2.RelativeTo(b1);
+
+    EXPECT_NEAR(a.Translation().X().to<double>(),
+                b.Translation().X().to<double>(), 1E-9);
+    EXPECT_NEAR(a.Translation().Y().to<double>(),
+                b.Translation().Y().to<double>(), 1E-9);
+    EXPECT_NEAR(a.Rotation().Radians().to<double>(),
+                b.Rotation().Radians().to<double>(), 1E-9);
+  }
+}
+
+TEST(TrajectoryTransforms, TransformBy) {
+  frc::TrajectoryConfig config{3_mps, 3_mps_sq};
+  auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
+      frc::Pose2d{}, {}, frc::Pose2d{1_m, 1_m, frc::Rotation2d(90_deg)},
+      config);
+
+  auto transformedTrajectory =
+      trajectory.TransformBy({{1_m, 2_m}, frc::Rotation2d(30_deg)});
+
+  auto firstPose = transformedTrajectory.Sample(0_s).pose;
+
+  EXPECT_NEAR(firstPose.Translation().X().to<double>(), 1.0, 1E-9);
+  EXPECT_NEAR(firstPose.Translation().Y().to<double>(), 2.0, 1E-9);
+  EXPECT_NEAR(firstPose.Rotation().Degrees().to<double>(), 30.0, 1E-9);
+
+  TestSameShapedTrajectory(trajectory.States(), transformedTrajectory.States());
+}
+
+TEST(TrajectoryTransforms, RelativeTo) {
+  frc::TrajectoryConfig config{3_mps, 3_mps_sq};
+  auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
+      frc::Pose2d{1_m, 2_m, frc::Rotation2d(30_deg)}, {},
+      frc::Pose2d{5_m, 7_m, frc::Rotation2d(90_deg)}, config);
+
+  auto transformedTrajectory =
+      trajectory.RelativeTo({1_m, 2_m, frc::Rotation2d(30_deg)});
+
+  auto firstPose = transformedTrajectory.Sample(0_s).pose;
+
+  EXPECT_NEAR(firstPose.Translation().X().to<double>(), 0, 1E-9);
+  EXPECT_NEAR(firstPose.Translation().Y().to<double>(), 0, 1E-9);
+  EXPECT_NEAR(firstPose.Rotation().Degrees().to<double>(), 0, 1E-9);
+
+  TestSameShapedTrajectory(trajectory.States(), transformedTrajectory.States());
+}
diff --git a/wpilibc/src/test/native/cpp/trajectory/TrapezoidProfileTest.cpp b/wpilibc/src/test/native/cpp/trajectory/TrapezoidProfileTest.cpp
new file mode 100644
index 0000000..bd9ffef
--- /dev/null
+++ b/wpilibc/src/test/native/cpp/trajectory/TrapezoidProfileTest.cpp
@@ -0,0 +1,233 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include "frc/trajectory/TrapezoidProfile.h"  // NOLINT(build/include_order)
+
+#include <chrono>
+#include <cmath>
+
+#include "gtest/gtest.h"
+
+static constexpr auto kDt = 10_ms;
+
+#define EXPECT_NEAR_UNITS(val1, val2, eps) \
+  EXPECT_LE(units::math::abs(val1 - val2), eps)
+
+#define EXPECT_LT_OR_NEAR_UNITS(val1, val2, eps) \
+  if (val1 <= val2) {                            \
+    EXPECT_LE(val1, val2);                       \
+  } else {                                       \
+    EXPECT_NEAR_UNITS(val1, val2, eps);          \
+  }
+
+TEST(TrapezoidProfileTest, ReachesGoal) {
+  frc::TrapezoidProfile<units::meter>::Constraints constraints{1.75_mps,
+                                                               0.75_mps_sq};
+  frc::TrapezoidProfile<units::meter>::State goal{3_m, 0_mps};
+  frc::TrapezoidProfile<units::meter>::State state;
+
+  for (int i = 0; i < 450; ++i) {
+    frc::TrapezoidProfile<units::meter> profile{constraints, goal, state};
+    state = profile.Calculate(kDt);
+  }
+  EXPECT_EQ(state, goal);
+}
+
+// Tests that decreasing the maximum velocity in the middle when it is already
+// moving faster than the new max is handled correctly
+TEST(TrapezoidProfileTest, PosContinousUnderVelChange) {
+  frc::TrapezoidProfile<units::meter>::Constraints constraints{1.75_mps,
+                                                               0.75_mps_sq};
+  frc::TrapezoidProfile<units::meter>::State goal{12_m, 0_mps};
+
+  frc::TrapezoidProfile<units::meter> profile{constraints, goal};
+  auto state = profile.Calculate(kDt);
+
+  auto lastPos = state.position;
+  for (int i = 0; i < 1600; ++i) {
+    if (i == 400) {
+      constraints.maxVelocity = 0.75_mps;
+    }
+
+    profile = frc::TrapezoidProfile<units::meter>{constraints, goal, state};
+    state = profile.Calculate(kDt);
+    auto estimatedVel = (state.position - lastPos) / kDt;
+
+    if (i >= 400) {
+      // Since estimatedVel can have floating point rounding errors, we check
+      // whether value is less than or within an error delta of the new
+      // constraint.
+      EXPECT_LT_OR_NEAR_UNITS(estimatedVel, constraints.maxVelocity, 1e-4_mps);
+
+      EXPECT_LE(state.velocity, constraints.maxVelocity);
+    }
+
+    lastPos = state.position;
+  }
+  EXPECT_EQ(state, goal);
+}
+
+// There is some somewhat tricky code for dealing with going backwards
+TEST(TrapezoidProfileTest, Backwards) {
+  frc::TrapezoidProfile<units::meter>::Constraints constraints{0.75_mps,
+                                                               0.75_mps_sq};
+  frc::TrapezoidProfile<units::meter>::State goal{-2_m, 0_mps};
+  frc::TrapezoidProfile<units::meter>::State state;
+
+  for (int i = 0; i < 400; ++i) {
+    frc::TrapezoidProfile<units::meter> profile{constraints, goal, state};
+    state = profile.Calculate(kDt);
+  }
+  EXPECT_EQ(state, goal);
+}
+
+TEST(TrapezoidProfileTest, SwitchGoalInMiddle) {
+  frc::TrapezoidProfile<units::meter>::Constraints constraints{0.75_mps,
+                                                               0.75_mps_sq};
+  frc::TrapezoidProfile<units::meter>::State goal{-2_m, 0_mps};
+  frc::TrapezoidProfile<units::meter>::State state;
+
+  for (int i = 0; i < 200; ++i) {
+    frc::TrapezoidProfile<units::meter> profile{constraints, goal, state};
+    state = profile.Calculate(kDt);
+  }
+  EXPECT_NE(state, goal);
+
+  goal = {0.0_m, 0.0_mps};
+  for (int i = 0; i < 550; ++i) {
+    frc::TrapezoidProfile<units::meter> profile{constraints, goal, state};
+    state = profile.Calculate(kDt);
+  }
+  EXPECT_EQ(state, goal);
+}
+
+// Checks to make sure that it hits top speed
+TEST(TrapezoidProfileTest, TopSpeed) {
+  frc::TrapezoidProfile<units::meter>::Constraints constraints{0.75_mps,
+                                                               0.75_mps_sq};
+  frc::TrapezoidProfile<units::meter>::State goal{4_m, 0_mps};
+  frc::TrapezoidProfile<units::meter>::State state;
+
+  for (int i = 0; i < 200; ++i) {
+    frc::TrapezoidProfile<units::meter> profile{constraints, goal, state};
+    state = profile.Calculate(kDt);
+  }
+  EXPECT_NEAR_UNITS(constraints.maxVelocity, state.velocity, 10e-5_mps);
+
+  for (int i = 0; i < 2000; ++i) {
+    frc::TrapezoidProfile<units::meter> profile{constraints, goal, state};
+    state = profile.Calculate(kDt);
+  }
+  EXPECT_EQ(state, goal);
+}
+
+TEST(TrapezoidProfileTest, TimingToCurrent) {
+  frc::TrapezoidProfile<units::meter>::Constraints constraints{0.75_mps,
+                                                               0.75_mps_sq};
+  frc::TrapezoidProfile<units::meter>::State goal{2_m, 0_mps};
+  frc::TrapezoidProfile<units::meter>::State state;
+
+  for (int i = 0; i < 400; i++) {
+    frc::TrapezoidProfile<units::meter> profile{constraints, goal, state};
+    state = profile.Calculate(kDt);
+    EXPECT_NEAR_UNITS(profile.TimeLeftUntil(state.position), 0_s, 2e-2_s);
+  }
+}
+
+TEST(TrapezoidProfileTest, TimingToGoal) {
+  using units::unit_cast;
+
+  frc::TrapezoidProfile<units::meter>::Constraints constraints{0.75_mps,
+                                                               0.75_mps_sq};
+  frc::TrapezoidProfile<units::meter>::State goal{2_m, 0_mps};
+
+  frc::TrapezoidProfile<units::meter> profile{constraints, goal};
+  auto state = profile.Calculate(kDt);
+
+  auto predictedTimeLeft = profile.TimeLeftUntil(goal.position);
+  bool reachedGoal = false;
+  for (int i = 0; i < 400; i++) {
+    profile = frc::TrapezoidProfile<units::meter>(constraints, goal, state);
+    state = profile.Calculate(kDt);
+    if (!reachedGoal && state == goal) {
+      // Expected value using for loop index is just an approximation since the
+      // time left in the profile doesn't increase linearly at the endpoints
+      EXPECT_NEAR(unit_cast<double>(predictedTimeLeft), i / 100.0, 0.25);
+      reachedGoal = true;
+    }
+  }
+}
+
+TEST(TrapezoidProfileTest, TimingBeforeGoal) {
+  using units::unit_cast;
+
+  frc::TrapezoidProfile<units::meter>::Constraints constraints{0.75_mps,
+                                                               0.75_mps_sq};
+  frc::TrapezoidProfile<units::meter>::State goal{2_m, 0_mps};
+
+  frc::TrapezoidProfile<units::meter> profile{constraints, goal};
+  auto state = profile.Calculate(kDt);
+
+  auto predictedTimeLeft = profile.TimeLeftUntil(1_m);
+  bool reachedGoal = false;
+  for (int i = 0; i < 400; i++) {
+    profile = frc::TrapezoidProfile<units::meter>(constraints, goal, state);
+    state = profile.Calculate(kDt);
+    if (!reachedGoal &&
+        (units::math::abs(state.velocity - 1_mps) < 10e-5_mps)) {
+      EXPECT_NEAR(unit_cast<double>(predictedTimeLeft), i / 100.0, 2e-2);
+      reachedGoal = true;
+    }
+  }
+}
+
+TEST(TrapezoidProfileTest, TimingToNegativeGoal) {
+  using units::unit_cast;
+
+  frc::TrapezoidProfile<units::meter>::Constraints constraints{0.75_mps,
+                                                               0.75_mps_sq};
+  frc::TrapezoidProfile<units::meter>::State goal{-2_m, 0_mps};
+
+  frc::TrapezoidProfile<units::meter> profile{constraints, goal};
+  auto state = profile.Calculate(kDt);
+
+  auto predictedTimeLeft = profile.TimeLeftUntil(goal.position);
+  bool reachedGoal = false;
+  for (int i = 0; i < 400; i++) {
+    profile = frc::TrapezoidProfile<units::meter>(constraints, goal, state);
+    state = profile.Calculate(kDt);
+    if (!reachedGoal && state == goal) {
+      // Expected value using for loop index is just an approximation since the
+      // time left in the profile doesn't increase linearly at the endpoints
+      EXPECT_NEAR(unit_cast<double>(predictedTimeLeft), i / 100.0, 0.25);
+      reachedGoal = true;
+    }
+  }
+}
+
+TEST(TrapezoidProfileTest, TimingBeforeNegativeGoal) {
+  using units::unit_cast;
+
+  frc::TrapezoidProfile<units::meter>::Constraints constraints{0.75_mps,
+                                                               0.75_mps_sq};
+  frc::TrapezoidProfile<units::meter>::State goal{-2_m, 0_mps};
+
+  frc::TrapezoidProfile<units::meter> profile{constraints, goal};
+  auto state = profile.Calculate(kDt);
+
+  auto predictedTimeLeft = profile.TimeLeftUntil(-1_m);
+  bool reachedGoal = false;
+  for (int i = 0; i < 400; i++) {
+    profile = frc::TrapezoidProfile<units::meter>(constraints, goal, state);
+    state = profile.Calculate(kDt);
+    if (!reachedGoal &&
+        (units::math::abs(state.velocity + 1_mps) < 10e-5_mps)) {
+      EXPECT_NEAR(unit_cast<double>(predictedTimeLeft), i / 100.0, 2e-2);
+      reachedGoal = true;
+    }
+  }
+}
diff --git a/wpilibc/src/test/native/include/MockSpeedController.h b/wpilibc/src/test/native/include/MockSpeedController.h
new file mode 100644
index 0000000..e0c788f
--- /dev/null
+++ b/wpilibc/src/test/native/include/MockSpeedController.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/SpeedController.h"
+
+namespace frc {
+
+class MockSpeedController : public SpeedController {
+ public:
+  void Set(double speed) override;
+  double Get() const override;
+  void SetInverted(bool isInverted) override;
+  bool GetInverted() const override;
+  void Disable() override;
+  void StopMotor() override;
+
+  void PIDWrite(double output) override;
+
+ private:
+  double m_speed = 0.0;
+  bool m_isInverted = false;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/test/native/include/shuffleboard/MockActuatorSendable.h b/wpilibc/src/test/native/include/shuffleboard/MockActuatorSendable.h
new file mode 100644
index 0000000..1cba8e3
--- /dev/null
+++ b/wpilibc/src/test/native/include/shuffleboard/MockActuatorSendable.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2018-2019 FIRST. All Rights Reserved.                        */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/StringRef.h>
+
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableHelper.h"
+
+namespace frc {
+
+/**
+ * A mock sendable that marks itself as an actuator.
+ */
+class MockActuatorSendable : public Sendable,
+                             public SendableHelper<MockActuatorSendable> {
+ public:
+  explicit MockActuatorSendable(wpi::StringRef name);
+
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/test/native/include/trajectory/TestTrajectory.h b/wpilibc/src/test/native/include/trajectory/TestTrajectory.h
new file mode 100644
index 0000000..4a496d7
--- /dev/null
+++ b/wpilibc/src/test/native/include/trajectory/TestTrajectory.h
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <utility>
+#include <vector>
+
+#include "frc/trajectory/Trajectory.h"
+#include "frc/trajectory/TrajectoryGenerator.h"
+#include "frc/trajectory/constraint/TrajectoryConstraint.h"
+
+namespace frc {
+class TestTrajectory {
+ public:
+  static Trajectory GetTrajectory(TrajectoryConfig& config) {
+    // 2018 cross scale auto waypoints
+    const Pose2d sideStart{1.54_ft, 23.23_ft, Rotation2d(180_deg)};
+    const Pose2d crossScale{23.7_ft, 6.8_ft, Rotation2d(-160_deg)};
+
+    config.SetReversed(true);
+
+    auto vector = std::vector<Translation2d>{
+        (sideStart + Transform2d{Translation2d(-13_ft, 0_ft), Rotation2d()})
+            .Translation(),
+        (sideStart +
+         Transform2d{Translation2d(-19.5_ft, 5.0_ft), Rotation2d(-90_deg)})
+            .Translation()};
+
+    return TrajectoryGenerator::GenerateTrajectory(sideStart, vector,
+                                                   crossScale, config);
+  }
+};
+
+}  // namespace frc
diff --git a/wpilibc/wpilibc-config.cmake.in b/wpilibc/wpilibc-config.cmake.in
new file mode 100644
index 0000000..4332c55
--- /dev/null
+++ b/wpilibc/wpilibc-config.cmake.in
@@ -0,0 +1,9 @@
+include(CMakeFindDependencyMacro)
+@FILENAME_DEP_REPLACE@
+@WPIUTIL_DEP_REPLACE@
+@NTCORE_DEP_REPLACE@
+@CSCORE_DEP_REPLACE@
+@CAMERASERVER_DEP_REPLACE@
+@HAL_DEP_REPLACE@
+
+include(${SELF_DIR}/wpilibc.cmake)