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

Change-Id: I3c07f85ed32ab8b97db765a9b43f2a6ce7da964a
diff --git a/hal/src/main/native/cpp/Main.cpp b/hal/src/main/native/cpp/Main.cpp
new file mode 100644
index 0000000..a37c2b0
--- /dev/null
+++ b/hal/src/main/native/cpp/Main.cpp
@@ -0,0 +1,64 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "hal/Main.h"
+
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+
+static void DefaultMain(void*);
+static void DefaultExit(void*);
+
+static bool gHasMain = false;
+static void* gMainParam = nullptr;
+static void (*gMainFunc)(void*) = DefaultMain;
+static void (*gExitFunc)(void*) = DefaultExit;
+static bool gExited = false;
+struct MainObj {
+  wpi::mutex gExitMutex;
+  wpi::condition_variable gExitCv;
+};
+
+static MainObj* mainObj;
+
+static void DefaultMain(void*) {
+  std::unique_lock lock{mainObj->gExitMutex};
+  mainObj->gExitCv.wait(lock, [] { return gExited; });
+}
+
+static void DefaultExit(void*) {
+  std::lock_guard lock{mainObj->gExitMutex};
+  gExited = true;
+  mainObj->gExitCv.notify_all();
+}
+
+namespace hal {
+namespace init {
+void InitializeMain() {
+  static MainObj mO;
+  mainObj = &mO;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+void HAL_SetMain(void* param, void (*mainFunc)(void*),
+                 void (*exitFunc)(void*)) {
+  gHasMain = true;
+  gMainParam = param;
+  gMainFunc = mainFunc;
+  gExitFunc = exitFunc;
+}
+
+HAL_Bool HAL_HasMain(void) { return gHasMain; }
+
+void HAL_RunMain(void) { gMainFunc(gMainParam); }
+
+void HAL_ExitMain(void) { gExitFunc(gMainParam); }
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/cpp/fpga_clock.cpp b/hal/src/main/native/cpp/cpp/fpga_clock.cpp
new file mode 100644
index 0000000..bcec155
--- /dev/null
+++ b/hal/src/main/native/cpp/cpp/fpga_clock.cpp
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "hal/cpp/fpga_clock.h"
+
+#include <wpi/raw_ostream.h>
+
+#include "hal/HAL.h"
+
+namespace hal {
+const fpga_clock::time_point fpga_clock::min_time =
+    fpga_clock::time_point(fpga_clock::duration(
+        std::numeric_limits<fpga_clock::duration::rep>::min()));
+
+fpga_clock::time_point fpga_clock::now() noexcept {
+  int32_t status = 0;
+  uint64_t currentTime = HAL_GetFPGATime(&status);
+  if (status != 0) {
+    wpi::errs()
+        << "Call to HAL_GetFPGATime failed in fpga_clock::now() with status "
+        << status
+        << ". Initialization might have failed. Time will not be correct\n";
+    wpi::errs().flush();
+    return epoch();
+  }
+  return time_point(std::chrono::microseconds(currentTime));
+}
+}  // namespace hal
diff --git a/hal/src/main/native/cpp/handles/HandlesInternal.cpp b/hal/src/main/native/cpp/handles/HandlesInternal.cpp
new file mode 100644
index 0000000..5e66ce1
--- /dev/null
+++ b/hal/src/main/native/cpp/handles/HandlesInternal.cpp
@@ -0,0 +1,95 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "hal/handles/HandlesInternal.h"
+
+#include <algorithm>
+
+#include <wpi/SmallVector.h>
+#include <wpi/mutex.h>
+
+namespace hal {
+static wpi::SmallVector<HandleBase*, 32>* globalHandles = nullptr;
+static wpi::mutex globalHandleMutex;
+HandleBase::HandleBase() {
+  static wpi::SmallVector<HandleBase*, 32> gH;
+  std::scoped_lock lock(globalHandleMutex);
+  if (!globalHandles) {
+    globalHandles = &gH;
+  }
+
+  auto index = std::find(globalHandles->begin(), globalHandles->end(), this);
+  if (index == globalHandles->end()) {
+    globalHandles->push_back(this);
+  } else {
+    *index = this;
+  }
+}
+HandleBase::~HandleBase() {
+  std::scoped_lock lock(globalHandleMutex);
+  auto index = std::find(globalHandles->begin(), globalHandles->end(), this);
+  if (index != globalHandles->end()) {
+    *index = nullptr;
+  }
+}
+void HandleBase::ResetHandles() {
+  m_version++;
+  if (m_version > 255) {
+    m_version = 0;
+  }
+}
+void HandleBase::ResetGlobalHandles() {
+  std::unique_lock lock(globalHandleMutex);
+  for (auto&& i : *globalHandles) {
+    if (i != nullptr) {
+      lock.unlock();
+      i->ResetHandles();
+      lock.lock();
+    }
+  }
+}
+HAL_PortHandle createPortHandle(uint8_t channel, uint8_t module) {
+  // set last 8 bits, then shift to first 8 bits
+  HAL_PortHandle handle = static_cast<HAL_PortHandle>(HAL_HandleEnum::Port);
+  handle = handle << 24;
+  // shift module and add to 3rd set of 8 bits
+  int32_t temp = module;
+  temp = (temp << 8) & 0xff00;
+  handle += temp;
+  // add channel to last 8 bits
+  handle += channel;
+  return handle;
+}
+HAL_PortHandle createPortHandleForSPI(uint8_t channel) {
+  // set last 8 bits, then shift to first 8 bits
+  HAL_PortHandle handle = static_cast<HAL_PortHandle>(HAL_HandleEnum::Port);
+  handle = handle << 16;
+  // set second set up bits to 1
+  int32_t temp = 1;
+  temp = (temp << 8) & 0xff00;
+  handle += temp;
+  // shift to last set of bits
+  handle = handle << 8;
+  // add channel to last 8 bits
+  handle += channel;
+  return handle;
+}
+HAL_Handle createHandle(int16_t index, HAL_HandleEnum handleType,
+                        int16_t version) {
+  if (index < 0) return HAL_kInvalidHandle;
+  uint8_t hType = static_cast<uint8_t>(handleType);
+  if (hType == 0 || hType > 127) return HAL_kInvalidHandle;
+  // set last 8 bits, then shift to first 8 bits
+  HAL_Handle handle = hType;
+  handle = handle << 8;
+  handle += static_cast<uint8_t>(version);
+  handle = handle << 16;
+  // add index to set last 16 bits
+  handle += index;
+  return handle;
+}
+}  // namespace hal
diff --git a/hal/src/main/native/cpp/jni/AccelerometerJNI.cpp b/hal/src/main/native/cpp/jni/AccelerometerJNI.cpp
new file mode 100644
index 0000000..6d0d256
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/AccelerometerJNI.cpp
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "edu_wpi_first_hal_AccelerometerJNI.h"
+#include "hal/Accelerometer.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_AccelerometerJNI
+ * Method:    setAccelerometerActive
+ * Signature: (Z)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AccelerometerJNI_setAccelerometerActive
+  (JNIEnv*, jclass, jboolean active)
+{
+  HAL_SetAccelerometerActive(active);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AccelerometerJNI
+ * Method:    setAccelerometerRange
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AccelerometerJNI_setAccelerometerRange
+  (JNIEnv*, jclass, jint range)
+{
+  HAL_SetAccelerometerRange((HAL_AccelerometerRange)range);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AccelerometerJNI
+ * Method:    getAccelerometerX
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AccelerometerJNI_getAccelerometerX
+  (JNIEnv*, jclass)
+{
+  return HAL_GetAccelerometerX();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AccelerometerJNI
+ * Method:    getAccelerometerY
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AccelerometerJNI_getAccelerometerY
+  (JNIEnv*, jclass)
+{
+  return HAL_GetAccelerometerY();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AccelerometerJNI
+ * Method:    getAccelerometerZ
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AccelerometerJNI_getAccelerometerZ
+  (JNIEnv*, jclass)
+{
+  return HAL_GetAccelerometerZ();
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/AddressableLEDJNI.cpp b/hal/src/main/native/cpp/jni/AddressableLEDJNI.cpp
new file mode 100644
index 0000000..3f76e6a
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/AddressableLEDJNI.cpp
@@ -0,0 +1,145 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <wpi/jni_util.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_AddressableLEDJNI.h"
+#include "hal/AddressableLED.h"
+
+using namespace frc;
+using namespace wpi::java;
+
+static_assert(sizeof(jbyte) * 4 == sizeof(HAL_AddressableLEDData));
+
+extern "C" {
+/*
+ * Class:     edu_wpi_first_hal_AddressableLEDJNI
+ * Method:    initialize
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AddressableLEDJNI_initialize
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  auto ret = HAL_InitializeAddressableLED(
+      static_cast<HAL_DigitalHandle>(handle), &status);
+  CheckStatus(env, status);
+  return ret;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AddressableLEDJNI
+ * Method:    free
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AddressableLEDJNI_free
+  (JNIEnv* env, jclass, jint handle)
+{
+  HAL_FreeAddressableLED(static_cast<HAL_AddressableLEDHandle>(handle));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AddressableLEDJNI
+ * Method:    setLength
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AddressableLEDJNI_setLength
+  (JNIEnv* env, jclass, jint handle, jint length)
+{
+  int32_t status = 0;
+  HAL_SetAddressableLEDLength(static_cast<HAL_AddressableLEDHandle>(handle),
+                              length, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AddressableLEDJNI
+ * Method:    setData
+ * Signature: (I[B)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AddressableLEDJNI_setData
+  (JNIEnv* env, jclass, jint handle, jbyteArray arr)
+{
+  int32_t status = 0;
+  JByteArrayRef jArrRef{env, arr};
+  auto arrRef = jArrRef.array();
+  HAL_WriteAddressableLEDData(
+      static_cast<HAL_AddressableLEDHandle>(handle),
+      reinterpret_cast<const HAL_AddressableLEDData*>(arrRef.data()),
+      arrRef.size() / 4, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AddressableLEDJNI
+ * Method:    setBitTiming
+ * Signature: (IIIII)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AddressableLEDJNI_setBitTiming
+  (JNIEnv* env, jclass, jint handle, jint lowTime0, jint highTime0,
+   jint lowTime1, jint highTime1)
+{
+  int32_t status = 0;
+  HAL_SetAddressableLEDBitTiming(static_cast<HAL_AddressableLEDHandle>(handle),
+                                 lowTime0, highTime0, lowTime1, highTime1,
+                                 &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AddressableLEDJNI
+ * Method:    setSyncTime
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AddressableLEDJNI_setSyncTime
+  (JNIEnv* env, jclass, jint handle, jint syncTime)
+{
+  int32_t status = 0;
+  HAL_SetAddressableLEDSyncTime(static_cast<HAL_AddressableLEDHandle>(handle),
+                                syncTime, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AddressableLEDJNI
+ * Method:    start
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AddressableLEDJNI_start
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  HAL_StartAddressableLEDOutput(static_cast<HAL_AddressableLEDHandle>(handle),
+                                &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AddressableLEDJNI
+ * Method:    stop
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AddressableLEDJNI_stop
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  HAL_StopAddressableLEDOutput(static_cast<HAL_AddressableLEDHandle>(handle),
+                               &status);
+  CheckStatus(env, status);
+}
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/AnalogGyroJNI.cpp b/hal/src/main/native/cpp/jni/AnalogGyroJNI.cpp
new file mode 100644
index 0000000..35b7414
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/AnalogGyroJNI.cpp
@@ -0,0 +1,194 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_AnalogGyroJNI.h"
+#include "hal/AnalogGyro.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace frc;
+
+extern "C" {
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    initializeAnalogGyro
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_initializeAnalogGyro
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_GyroHandle handle =
+      HAL_InitializeAnalogGyro((HAL_AnalogInputHandle)id, &status);
+  // Analog input does range checking, so we don't need to do so.
+  CheckStatusForceThrow(env, status);
+  return (jint)handle;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    setupAnalogGyro
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_setupAnalogGyro
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_SetupAnalogGyro((HAL_GyroHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    freeAnalogGyro
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_freeAnalogGyro
+  (JNIEnv* env, jclass, jint id)
+{
+  HAL_FreeAnalogGyro((HAL_GyroHandle)id);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    setAnalogGyroParameters
+ * Signature: (IDDI)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_setAnalogGyroParameters
+  (JNIEnv* env, jclass, jint id, jdouble vPDPS, jdouble offset, jint center)
+{
+  int32_t status = 0;
+  HAL_SetAnalogGyroParameters((HAL_GyroHandle)id, vPDPS, offset, center,
+                              &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    setAnalogGyroVoltsPerDegreePerSecond
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_setAnalogGyroVoltsPerDegreePerSecond
+  (JNIEnv* env, jclass, jint id, jdouble vPDPS)
+{
+  int32_t status = 0;
+  HAL_SetAnalogGyroVoltsPerDegreePerSecond((HAL_GyroHandle)id, vPDPS, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    resetAnalogGyro
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_resetAnalogGyro
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_ResetAnalogGyro((HAL_GyroHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    calibrateAnalogGyro
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_calibrateAnalogGyro
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_CalibrateAnalogGyro((HAL_GyroHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    setAnalogGyroDeadband
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_setAnalogGyroDeadband
+  (JNIEnv* env, jclass, jint id, jdouble deadband)
+{
+  int32_t status = 0;
+  HAL_SetAnalogGyroDeadband((HAL_GyroHandle)id, deadband, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    getAnalogGyroAngle
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_getAnalogGyroAngle
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jdouble value = HAL_GetAnalogGyroAngle((HAL_GyroHandle)id, &status);
+  CheckStatus(env, status);
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    getAnalogGyroRate
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_getAnalogGyroRate
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jdouble value = HAL_GetAnalogGyroRate((HAL_GyroHandle)id, &status);
+  CheckStatus(env, status);
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    getAnalogGyroOffset
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_getAnalogGyroOffset
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jdouble value = HAL_GetAnalogGyroOffset((HAL_GyroHandle)id, &status);
+  CheckStatus(env, status);
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    getAnalogGyroCenter
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_getAnalogGyroCenter
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jint value = HAL_GetAnalogGyroCenter((HAL_GyroHandle)id, &status);
+  CheckStatus(env, status);
+  return value;
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/AnalogJNI.cpp b/hal/src/main/native/cpp/jni/AnalogJNI.cpp
new file mode 100644
index 0000000..5571d55
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/AnalogJNI.cpp
@@ -0,0 +1,669 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_AnalogJNI.h"
+#include "hal/AnalogAccumulator.h"
+#include "hal/AnalogInput.h"
+#include "hal/AnalogOutput.h"
+#include "hal/AnalogTrigger.h"
+#include "hal/Ports.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    initializeAnalogInputPort
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_initializeAnalogInputPort
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  auto analog = HAL_InitializeAnalogInputPort((HAL_PortHandle)id, &status);
+  CheckStatusRange(env, status, 0, HAL_GetNumAnalogInputs(),
+                   hal::getPortHandleChannel((HAL_PortHandle)id));
+  return (jint)analog;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    freeAnalogInputPort
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_freeAnalogInputPort
+  (JNIEnv* env, jclass, jint id)
+{
+  HAL_FreeAnalogInputPort((HAL_AnalogInputHandle)id);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    initializeAnalogOutputPort
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_initializeAnalogOutputPort
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_AnalogOutputHandle analog =
+      HAL_InitializeAnalogOutputPort((HAL_PortHandle)id, &status);
+  CheckStatusRange(env, status, 0, HAL_GetNumAnalogOutputs(),
+                   hal::getPortHandleChannel((HAL_PortHandle)id));
+  return (jlong)analog;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    freeAnalogOutputPort
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_freeAnalogOutputPort
+  (JNIEnv* env, jclass, jint id)
+{
+  HAL_FreeAnalogOutputPort((HAL_AnalogOutputHandle)id);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    checkAnalogModule
+ * Signature: (B)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_checkAnalogModule
+  (JNIEnv*, jclass, jbyte value)
+{
+  jboolean returnValue = HAL_CheckAnalogModule(value);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    checkAnalogInputChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_checkAnalogInputChannel
+  (JNIEnv*, jclass, jint value)
+{
+  jboolean returnValue = HAL_CheckAnalogInputChannel(value);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    checkAnalogOutputChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_checkAnalogOutputChannel
+  (JNIEnv*, jclass, jint value)
+{
+  jboolean returnValue = HAL_CheckAnalogOutputChannel(value);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogInputSimDevice
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogInputSimDevice
+  (JNIEnv* env, jclass, jint handle, jint device)
+{
+  HAL_SetAnalogInputSimDevice((HAL_AnalogInputHandle)handle,
+                              (HAL_SimDeviceHandle)device);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogOutput
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogOutput
+  (JNIEnv* env, jclass, jint id, jdouble voltage)
+{
+  int32_t status = 0;
+  HAL_SetAnalogOutput((HAL_AnalogOutputHandle)id, voltage, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogOutput
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogOutput
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  double val = HAL_GetAnalogOutput((HAL_AnalogOutputHandle)id, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogSampleRate
+ * Signature: (D)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogSampleRate
+  (JNIEnv* env, jclass, jdouble value)
+{
+  int32_t status = 0;
+  HAL_SetAnalogSampleRate(value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogSampleRate
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogSampleRate
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double returnValue = HAL_GetAnalogSampleRate(&status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogAverageBits
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogAverageBits
+  (JNIEnv* env, jclass, jint id, jint value)
+{
+  int32_t status = 0;
+  HAL_SetAnalogAverageBits((HAL_AnalogInputHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogAverageBits
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogAverageBits
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetAnalogAverageBits((HAL_AnalogInputHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogOversampleBits
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogOversampleBits
+  (JNIEnv* env, jclass, jint id, jint value)
+{
+  int32_t status = 0;
+  HAL_SetAnalogOversampleBits((HAL_AnalogInputHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogOversampleBits
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogOversampleBits
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetAnalogOversampleBits((HAL_AnalogInputHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogValue
+ * Signature: (I)S
+ */
+JNIEXPORT jshort JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogValue
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jshort returnValue = HAL_GetAnalogValue((HAL_AnalogInputHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogAverageValue
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogAverageValue
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetAnalogAverageValue((HAL_AnalogInputHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogVoltsToValue
+ * Signature: (ID)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogVoltsToValue
+  (JNIEnv* env, jclass, jint id, jdouble voltageValue)
+{
+  int32_t status = 0;
+  jint returnValue = HAL_GetAnalogVoltsToValue((HAL_AnalogInputHandle)id,
+                                               voltageValue, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogVoltage
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogVoltage
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jdouble returnValue =
+      HAL_GetAnalogVoltage((HAL_AnalogInputHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogAverageVoltage
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogAverageVoltage
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jdouble returnValue =
+      HAL_GetAnalogAverageVoltage((HAL_AnalogInputHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogLSBWeight
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogLSBWeight
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+
+  jint returnValue = HAL_GetAnalogLSBWeight((HAL_AnalogInputHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogOffset
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogOffset
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+
+  jint returnValue = HAL_GetAnalogOffset((HAL_AnalogInputHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    isAccumulatorChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_isAccumulatorChannel
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+
+  jboolean returnValue =
+      HAL_IsAccumulatorChannel((HAL_AnalogInputHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    initAccumulator
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_initAccumulator
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_InitAccumulator((HAL_AnalogInputHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    resetAccumulator
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_resetAccumulator
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_ResetAccumulator((HAL_AnalogInputHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAccumulatorCenter
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAccumulatorCenter
+  (JNIEnv* env, jclass, jint id, jint center)
+{
+  int32_t status = 0;
+  HAL_SetAccumulatorCenter((HAL_AnalogInputHandle)id, center, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAccumulatorDeadband
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAccumulatorDeadband
+  (JNIEnv* env, jclass, jint id, jint deadband)
+{
+  int32_t status = 0;
+  HAL_SetAccumulatorDeadband((HAL_AnalogInputHandle)id, deadband, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAccumulatorValue
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAccumulatorValue
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jlong returnValue =
+      HAL_GetAccumulatorValue((HAL_AnalogInputHandle)id, &status);
+  CheckStatus(env, status);
+
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAccumulatorCount
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAccumulatorCount
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetAccumulatorCount((HAL_AnalogInputHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAccumulatorOutput
+ * Signature: (ILjava/lang/Object;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAccumulatorOutput
+  (JNIEnv* env, jclass, jint id, jobject accumulatorResult)
+{
+  int32_t status = 0;
+  int64_t value = 0;
+  int64_t count = 0;
+  HAL_GetAccumulatorOutput((HAL_AnalogInputHandle)id, &value, &count, &status);
+  SetAccumulatorResultObject(env, accumulatorResult, value, count);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    initializeAnalogTrigger
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_initializeAnalogTrigger
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_AnalogTriggerHandle analogTrigger =
+      HAL_InitializeAnalogTrigger((HAL_AnalogInputHandle)id, &status);
+  CheckStatus(env, status);
+  return (jint)analogTrigger;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    initializeAnalogTriggerDutyCycle
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_initializeAnalogTriggerDutyCycle
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_AnalogTriggerHandle analogTrigger =
+      HAL_InitializeAnalogTriggerDutyCycle((HAL_DutyCycleHandle)id, &status);
+  CheckStatus(env, status);
+  return (jint)analogTrigger;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    cleanAnalogTrigger
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_cleanAnalogTrigger
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_CleanAnalogTrigger((HAL_AnalogTriggerHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogTriggerLimitsRaw
+ * Signature: (III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogTriggerLimitsRaw
+  (JNIEnv* env, jclass, jint id, jint lower, jint upper)
+{
+  int32_t status = 0;
+  HAL_SetAnalogTriggerLimitsRaw((HAL_AnalogTriggerHandle)id, lower, upper,
+                                &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogTriggerLimitsDutyCycle
+ * Signature: (IDD)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogTriggerLimitsDutyCycle
+  (JNIEnv* env, jclass, jint id, jdouble lower, jdouble upper)
+{
+  int32_t status = 0;
+  HAL_SetAnalogTriggerLimitsDutyCycle((HAL_AnalogTriggerHandle)id, lower, upper,
+                                      &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogTriggerLimitsVoltage
+ * Signature: (IDD)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogTriggerLimitsVoltage
+  (JNIEnv* env, jclass, jint id, jdouble lower, jdouble upper)
+{
+  int32_t status = 0;
+  HAL_SetAnalogTriggerLimitsVoltage((HAL_AnalogTriggerHandle)id, lower, upper,
+                                    &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogTriggerAveraged
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogTriggerAveraged
+  (JNIEnv* env, jclass, jint id, jboolean averaged)
+{
+  int32_t status = 0;
+  HAL_SetAnalogTriggerAveraged((HAL_AnalogTriggerHandle)id, averaged, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogTriggerFiltered
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogTriggerFiltered
+  (JNIEnv* env, jclass, jint id, jboolean filtered)
+{
+  int32_t status = 0;
+  HAL_SetAnalogTriggerFiltered((HAL_AnalogTriggerHandle)id, filtered, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogTriggerInWindow
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogTriggerInWindow
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jboolean val =
+      HAL_GetAnalogTriggerInWindow((HAL_AnalogTriggerHandle)id, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogTriggerTriggerState
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogTriggerTriggerState
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jboolean val =
+      HAL_GetAnalogTriggerTriggerState((HAL_AnalogTriggerHandle)id, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogTriggerOutput
+ * Signature: (II)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogTriggerOutput
+  (JNIEnv* env, jclass, jint id, jint type)
+{
+  int32_t status = 0;
+  jboolean val = HAL_GetAnalogTriggerOutput(
+      (HAL_AnalogTriggerHandle)id, (HAL_AnalogTriggerType)type, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogTriggerFPGAIndex
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogTriggerFPGAIndex
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  auto val =
+      HAL_GetAnalogTriggerFPGAIndex((HAL_AnalogTriggerHandle)id, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/CANAPIJNI.cpp b/hal/src/main/native/cpp/jni/CANAPIJNI.cpp
new file mode 100644
index 0000000..7ac7cf6
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/CANAPIJNI.cpp
@@ -0,0 +1,221 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include <wpi/SmallString.h>
+#include <wpi/jni_util.h>
+#include <wpi/raw_ostream.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_CANAPIJNI.h"
+#include "hal/CAN.h"
+#include "hal/CANAPI.h"
+#include "hal/Errors.h"
+
+using namespace frc;
+using namespace wpi::java;
+
+extern "C" {
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    initializeCAN
+ * Signature: (III)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_initializeCAN
+  (JNIEnv* env, jclass, jint manufacturer, jint deviceId, jint deviceType)
+{
+  int32_t status = 0;
+  auto handle =
+      HAL_InitializeCAN(static_cast<HAL_CANManufacturer>(manufacturer),
+                        static_cast<int32_t>(deviceId),
+                        static_cast<HAL_CANDeviceType>(deviceType), &status);
+
+  CheckStatusForceThrow(env, status);
+  return handle;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    cleanCAN
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_cleanCAN
+  (JNIEnv* env, jclass, jint handle)
+{
+  HAL_CleanCAN(static_cast<HAL_CANHandle>(handle));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    writeCANPacket
+ * Signature: (I[BI)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_writeCANPacket
+  (JNIEnv* env, jclass, jint handle, jbyteArray data, jint apiId)
+{
+  auto halHandle = static_cast<HAL_CANHandle>(handle);
+  JByteArrayRef arr{env, data};
+  auto arrRef = arr.array();
+  int32_t status = 0;
+  HAL_WriteCANPacket(halHandle, reinterpret_cast<const uint8_t*>(arrRef.data()),
+                     arrRef.size(), apiId, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    writeCANPacketRepeating
+ * Signature: (I[BII)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_writeCANPacketRepeating
+  (JNIEnv* env, jclass, jint handle, jbyteArray data, jint apiId,
+   jint timeoutMs)
+{
+  auto halHandle = static_cast<HAL_CANHandle>(handle);
+  JByteArrayRef arr{env, data};
+  auto arrRef = arr.array();
+  int32_t status = 0;
+  HAL_WriteCANPacketRepeating(halHandle,
+                              reinterpret_cast<const uint8_t*>(arrRef.data()),
+                              arrRef.size(), apiId, timeoutMs, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    writeCANRTRFrame
+ * Signature: (III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_writeCANRTRFrame
+  (JNIEnv* env, jclass, jint handle, jint length, jint apiId)
+{
+  auto halHandle = static_cast<HAL_CANHandle>(handle);
+  int32_t status = 0;
+  HAL_WriteCANRTRFrame(halHandle, static_cast<int32_t>(length), apiId, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    stopCANPacketRepeating
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_stopCANPacketRepeating
+  (JNIEnv* env, jclass, jint handle, jint apiId)
+{
+  auto halHandle = static_cast<HAL_CANHandle>(handle);
+  int32_t status = 0;
+  HAL_StopCANPacketRepeating(halHandle, apiId, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    readCANPacketNew
+ * Signature: (IILjava/lang/Object;)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_readCANPacketNew
+  (JNIEnv* env, jclass, jint handle, jint apiId, jobject data)
+{
+  auto halHandle = static_cast<HAL_CANHandle>(handle);
+  uint8_t dataTemp[8];
+  int32_t dataLength = 0;
+  uint64_t timestamp = 0;
+  int32_t status = 0;
+  HAL_ReadCANPacketNew(halHandle, apiId, dataTemp, &dataLength, &timestamp,
+                       &status);
+  if (status == HAL_ERR_CANSessionMux_MessageNotFound) {
+    return false;
+  }
+  if (!CheckStatus(env, status)) {
+    return false;
+  }
+  if (dataLength > 8) dataLength = 8;
+
+  jbyteArray toSetArray = SetCANDataObject(env, data, dataLength, timestamp);
+  auto javaLen = env->GetArrayLength(toSetArray);
+  if (javaLen < dataLength) dataLength = javaLen;
+  env->SetByteArrayRegion(toSetArray, 0, dataLength,
+                          reinterpret_cast<jbyte*>(dataTemp));
+  return true;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    readCANPacketLatest
+ * Signature: (IILjava/lang/Object;)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_readCANPacketLatest
+  (JNIEnv* env, jclass, jint handle, jint apiId, jobject data)
+{
+  auto halHandle = static_cast<HAL_CANHandle>(handle);
+  uint8_t dataTemp[8];
+  int32_t dataLength = 0;
+  uint64_t timestamp = 0;
+  int32_t status = 0;
+  HAL_ReadCANPacketLatest(halHandle, apiId, dataTemp, &dataLength, &timestamp,
+                          &status);
+  if (status == HAL_ERR_CANSessionMux_MessageNotFound) {
+    return false;
+  }
+  if (!CheckStatus(env, status)) {
+    return false;
+  }
+  if (dataLength > 8) dataLength = 8;
+
+  jbyteArray toSetArray = SetCANDataObject(env, data, dataLength, timestamp);
+  auto javaLen = env->GetArrayLength(toSetArray);
+  if (javaLen < dataLength) dataLength = javaLen;
+  env->SetByteArrayRegion(toSetArray, 0, dataLength,
+                          reinterpret_cast<jbyte*>(dataTemp));
+  return true;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    readCANPacketTimeout
+ * Signature: (IIILjava/lang/Object;)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_readCANPacketTimeout
+  (JNIEnv* env, jclass, jint handle, jint apiId, jint timeoutMs, jobject data)
+{
+  auto halHandle = static_cast<HAL_CANHandle>(handle);
+  uint8_t dataTemp[8];
+  int32_t dataLength = 0;
+  uint64_t timestamp = 0;
+  int32_t status = 0;
+  HAL_ReadCANPacketTimeout(halHandle, apiId, dataTemp, &dataLength, &timestamp,
+                           timeoutMs, &status);
+  if (status == HAL_CAN_TIMEOUT ||
+      status == HAL_ERR_CANSessionMux_MessageNotFound) {
+    return false;
+  }
+  if (!CheckStatus(env, status)) {
+    return false;
+  }
+  if (dataLength > 8) dataLength = 8;
+
+  jbyteArray toSetArray = SetCANDataObject(env, data, dataLength, timestamp);
+  auto javaLen = env->GetArrayLength(toSetArray);
+  if (javaLen < dataLength) dataLength = javaLen;
+  env->SetByteArrayRegion(toSetArray, 0, dataLength,
+                          reinterpret_cast<jbyte*>(dataTemp));
+  return true;
+}
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/CANJNI.cpp b/hal/src/main/native/cpp/jni/CANJNI.cpp
new file mode 100644
index 0000000..9278c24
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/CANJNI.cpp
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include <wpi/SmallString.h>
+#include <wpi/jni_util.h>
+#include <wpi/raw_ostream.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_can_CANJNI.h"
+#include "hal/CAN.h"
+
+using namespace frc;
+using namespace wpi::java;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_can_CANJNI
+ * Method:    FRCNetCommCANSessionMuxSendMessage
+ * Signature: (I[BI)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_can_CANJNI_FRCNetCommCANSessionMuxSendMessage
+  (JNIEnv* env, jclass, jint messageID, jbyteArray data, jint periodMs)
+{
+  JByteArrayRef dataArray{env, data};
+
+  const uint8_t* dataBuffer =
+      reinterpret_cast<const uint8_t*>(dataArray.array().data());
+  uint8_t dataSize = dataArray.array().size();
+
+  int32_t status = 0;
+  HAL_CAN_SendMessage(messageID, dataBuffer, dataSize, periodMs, &status);
+  CheckCANStatus(env, status, messageID);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_can_CANJNI
+ * Method:    FRCNetCommCANSessionMuxReceiveMessage
+ * Signature: (Ljava/lang/Object;ILjava/lang/Object;)[B
+ */
+JNIEXPORT jbyteArray JNICALL
+Java_edu_wpi_first_hal_can_CANJNI_FRCNetCommCANSessionMuxReceiveMessage
+  (JNIEnv* env, jclass, jobject messageID, jint messageIDMask,
+   jobject timeStamp)
+{
+  uint32_t* messageIDPtr =
+      reinterpret_cast<uint32_t*>(env->GetDirectBufferAddress(messageID));
+  uint32_t* timeStampPtr =
+      reinterpret_cast<uint32_t*>(env->GetDirectBufferAddress(timeStamp));
+
+  uint8_t dataSize = 0;
+  uint8_t buffer[8];
+
+  int32_t status = 0;
+  HAL_CAN_ReceiveMessage(messageIDPtr, messageIDMask, buffer, &dataSize,
+                         timeStampPtr, &status);
+
+  if (!CheckCANStatus(env, status, *messageIDPtr)) return nullptr;
+  return MakeJByteArray(env,
+                        wpi::StringRef{reinterpret_cast<const char*>(buffer),
+                                       static_cast<size_t>(dataSize)});
+}
+
+/*
+ * Class:     edu_wpi_first_hal_can_CANJNI
+ * Method:    GetCANStatus
+ * Signature: (Ljava/lang/Object;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_can_CANJNI_GetCANStatus
+  (JNIEnv* env, jclass, jobject canStatus)
+{
+  float percentBusUtilization = 0;
+  uint32_t busOffCount = 0;
+  uint32_t txFullCount = 0;
+  uint32_t receiveErrorCount = 0;
+  uint32_t transmitErrorCount = 0;
+  int32_t status = 0;
+  HAL_CAN_GetCANStatus(&percentBusUtilization, &busOffCount, &txFullCount,
+                       &receiveErrorCount, &transmitErrorCount, &status);
+
+  if (!CheckStatus(env, status)) return;
+
+  SetCanStatusObject(env, canStatus, percentBusUtilization, busOffCount,
+                     txFullCount, receiveErrorCount, transmitErrorCount);
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/CompressorJNI.cpp b/hal/src/main/native/cpp/jni/CompressorJNI.cpp
new file mode 100644
index 0000000..75a5e0a
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/CompressorJNI.cpp
@@ -0,0 +1,233 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "HALUtil.h"
+#include "edu_wpi_first_hal_CompressorJNI.h"
+#include "hal/Compressor.h"
+#include "hal/Ports.h"
+#include "hal/Solenoid.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    initializeCompressor
+ * Signature: (B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_initializeCompressor
+  (JNIEnv* env, jclass, jbyte module)
+{
+  int32_t status = 0;
+  auto handle = HAL_InitializeCompressor(module, &status);
+  CheckStatusRange(env, status, 0, HAL_GetNumPCMModules(), module);
+
+  return (jint)handle;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    checkCompressorModule
+ * Signature: (B)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_checkCompressorModule
+  (JNIEnv* env, jclass, jbyte module)
+{
+  return HAL_CheckCompressorModule(module);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressor
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressor
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressor((HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    setCompressorClosedLoopControl
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_setCompressorClosedLoopControl
+  (JNIEnv* env, jclass, jint compressorHandle, jboolean value)
+{
+  int32_t status = 0;
+  HAL_SetCompressorClosedLoopControl((HAL_CompressorHandle)compressorHandle,
+                                     value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorClosedLoopControl
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorClosedLoopControl
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorClosedLoopControl(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorPressureSwitch
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorPressureSwitch
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorPressureSwitch(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorCurrent
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorCurrent
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  double val =
+      HAL_GetCompressorCurrent((HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorCurrentTooHighFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorCurrentTooHighFault
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorCurrentTooHighFault(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorCurrentTooHighStickyFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorCurrentTooHighStickyFault
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorCurrentTooHighStickyFault(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorShortedStickyFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorShortedStickyFault
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorShortedStickyFault(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorShortedFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorShortedFault
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorShortedFault(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorNotConnectedStickyFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorNotConnectedStickyFault
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorNotConnectedStickyFault(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorNotConnectedFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorNotConnectedFault
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorNotConnectedFault(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    clearAllPCMStickyFaults
+ * Signature: (B)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_clearAllPCMStickyFaults
+  (JNIEnv* env, jclass, jbyte module)
+{
+  int32_t status = 0;
+  HAL_ClearAllPCMStickyFaults(static_cast<int32_t>(module), &status);
+  CheckStatus(env, status);
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/ConstantsJNI.cpp b/hal/src/main/native/cpp/jni/ConstantsJNI.cpp
new file mode 100644
index 0000000..fb1ae0b
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/ConstantsJNI.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_ConstantsJNI.h"
+#include "hal/Constants.h"
+
+using namespace frc;
+
+extern "C" {
+/*
+ * Class:     edu_wpi_first_hal_ConstantsJNI
+ * Method:    getSystemClockTicksPerMicrosecond
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_ConstantsJNI_getSystemClockTicksPerMicrosecond
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetSystemClockTicksPerMicrosecond();
+  return value;
+}
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/CounterJNI.cpp b/hal/src/main/native/cpp/jni/CounterJNI.cpp
new file mode 100644
index 0000000..41dedab
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/CounterJNI.cpp
@@ -0,0 +1,370 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_CounterJNI.h"
+#include "hal/Counter.h"
+#include "hal/Errors.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    initializeCounter
+ * Signature: (ILjava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_CounterJNI_initializeCounter
+  (JNIEnv* env, jclass, jint mode, jobject index)
+{
+  jint* indexPtr = reinterpret_cast<jint*>(env->GetDirectBufferAddress(index));
+  int32_t status = 0;
+  auto counter = HAL_InitializeCounter(
+      (HAL_Counter_Mode)mode, reinterpret_cast<int32_t*>(indexPtr), &status);
+  CheckStatusForceThrow(env, status);
+  return (jint)counter;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    freeCounter
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_freeCounter
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_FreeCounter((HAL_CounterHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterAverageSize
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterAverageSize
+  (JNIEnv* env, jclass, jint id, jint value)
+{
+  int32_t status = 0;
+  HAL_SetCounterAverageSize((HAL_CounterHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterUpSource
+ * Signature: (III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterUpSource
+  (JNIEnv* env, jclass, jint id, jint digitalSourceHandle,
+   jint analogTriggerType)
+{
+  int32_t status = 0;
+  HAL_SetCounterUpSource((HAL_CounterHandle)id, (HAL_Handle)digitalSourceHandle,
+                         (HAL_AnalogTriggerType)analogTriggerType, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterUpSourceEdge
+ * Signature: (IZZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterUpSourceEdge
+  (JNIEnv* env, jclass, jint id, jboolean valueRise, jboolean valueFall)
+{
+  int32_t status = 0;
+  HAL_SetCounterUpSourceEdge((HAL_CounterHandle)id, valueRise, valueFall,
+                             &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    clearCounterUpSource
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_clearCounterUpSource
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_ClearCounterUpSource((HAL_CounterHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterDownSource
+ * Signature: (III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterDownSource
+  (JNIEnv* env, jclass, jint id, jint digitalSourceHandle,
+   jint analogTriggerType)
+{
+  int32_t status = 0;
+  HAL_SetCounterDownSource((HAL_CounterHandle)id,
+                           (HAL_Handle)digitalSourceHandle,
+                           (HAL_AnalogTriggerType)analogTriggerType, &status);
+  if (status == PARAMETER_OUT_OF_RANGE) {
+    ThrowIllegalArgumentException(env,
+                                  "Counter only supports DownSource in "
+                                  "TwoPulse and ExternalDirection modes.");
+    return;
+  }
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterDownSourceEdge
+ * Signature: (IZZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterDownSourceEdge
+  (JNIEnv* env, jclass, jint id, jboolean valueRise, jboolean valueFall)
+{
+  int32_t status = 0;
+  HAL_SetCounterDownSourceEdge((HAL_CounterHandle)id, valueRise, valueFall,
+                               &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    clearCounterDownSource
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_clearCounterDownSource
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_ClearCounterDownSource((HAL_CounterHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterUpDownMode
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterUpDownMode
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_SetCounterUpDownMode((HAL_CounterHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterExternalDirectionMode
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterExternalDirectionMode
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_SetCounterExternalDirectionMode((HAL_CounterHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterSemiPeriodMode
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterSemiPeriodMode
+  (JNIEnv* env, jclass, jint id, jboolean value)
+{
+  int32_t status = 0;
+  HAL_SetCounterSemiPeriodMode((HAL_CounterHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterPulseLengthMode
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterPulseLengthMode
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  int32_t status = 0;
+  HAL_SetCounterPulseLengthMode((HAL_CounterHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    getCounterSamplesToAverage
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_CounterJNI_getCounterSamplesToAverage
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetCounterSamplesToAverage((HAL_CounterHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterSamplesToAverage
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterSamplesToAverage
+  (JNIEnv* env, jclass, jint id, jint value)
+{
+  int32_t status = 0;
+  HAL_SetCounterSamplesToAverage((HAL_CounterHandle)id, value, &status);
+  if (status == PARAMETER_OUT_OF_RANGE) {
+    ThrowBoundaryException(env, value, 1, 127);
+    return;
+  }
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    resetCounter
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_resetCounter
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_ResetCounter((HAL_CounterHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    getCounter
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_CounterJNI_getCounter
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jint returnValue = HAL_GetCounter((HAL_CounterHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    getCounterPeriod
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_CounterJNI_getCounterPeriod
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jdouble returnValue = HAL_GetCounterPeriod((HAL_CounterHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterMaxPeriod
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterMaxPeriod
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  int32_t status = 0;
+  HAL_SetCounterMaxPeriod((HAL_CounterHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterUpdateWhenEmpty
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterUpdateWhenEmpty
+  (JNIEnv* env, jclass, jint id, jboolean value)
+{
+  int32_t status = 0;
+  HAL_SetCounterUpdateWhenEmpty((HAL_CounterHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    getCounterStopped
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CounterJNI_getCounterStopped
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jboolean returnValue = HAL_GetCounterStopped((HAL_CounterHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    getCounterDirection
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CounterJNI_getCounterDirection
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jboolean returnValue =
+      HAL_GetCounterDirection((HAL_CounterHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterReverseDirection
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterReverseDirection
+  (JNIEnv* env, jclass, jint id, jboolean value)
+{
+  int32_t status = 0;
+  HAL_SetCounterReverseDirection((HAL_CounterHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/DIOJNI.cpp b/hal/src/main/native/cpp/jni/DIOJNI.cpp
new file mode 100644
index 0000000..9c44b4c
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/DIOJNI.cpp
@@ -0,0 +1,265 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_DIOJNI.h"
+#include "hal/DIO.h"
+#include "hal/PWM.h"
+#include "hal/Ports.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    initializeDIOPort
+ * Signature: (IZ)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DIOJNI_initializeDIOPort
+  (JNIEnv* env, jclass, jint id, jboolean input)
+{
+  int32_t status = 0;
+  auto dio = HAL_InitializeDIOPort((HAL_PortHandle)id,
+                                   static_cast<uint8_t>(input), &status);
+  CheckStatusRange(env, status, 0, HAL_GetNumDigitalChannels(),
+                   hal::getPortHandleChannel((HAL_PortHandle)id));
+  return (jint)dio;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    checkDIOChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_DIOJNI_checkDIOChannel
+  (JNIEnv* env, jclass, jint channel)
+{
+  return HAL_CheckDIOChannel(channel);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    freeDIOPort
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_freeDIOPort
+  (JNIEnv* env, jclass, jint id)
+{
+  HAL_FreeDIOPort((HAL_DigitalHandle)id);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    setDIOSimDevice
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_setDIOSimDevice
+  (JNIEnv* env, jclass, jint handle, jint device)
+{
+  HAL_SetDIOSimDevice((HAL_DigitalHandle)handle, (HAL_SimDeviceHandle)device);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    setDIO
+ * Signature: (IS)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_setDIO
+  (JNIEnv* env, jclass, jint id, jshort value)
+{
+  int32_t status = 0;
+  HAL_SetDIO((HAL_DigitalHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    setDIODirection
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_setDIODirection
+  (JNIEnv* env, jclass, jint id, jboolean input)
+{
+  int32_t status = 0;
+  HAL_SetDIODirection((HAL_DigitalHandle)id, input, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    getDIO
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_DIOJNI_getDIO
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jboolean returnValue = HAL_GetDIO((HAL_DigitalHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    getDIODirection
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_DIOJNI_getDIODirection
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jboolean returnValue = HAL_GetDIODirection((HAL_DigitalHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    pulse
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_pulse
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  int32_t status = 0;
+  HAL_Pulse((HAL_DigitalHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    isPulsing
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_DIOJNI_isPulsing
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jboolean returnValue = HAL_IsPulsing((HAL_DigitalHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    isAnyPulsing
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_DIOJNI_isAnyPulsing
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  jboolean returnValue = HAL_IsAnyPulsing(&status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    getLoopTiming
+ * Signature: ()S
+ */
+JNIEXPORT jshort JNICALL
+Java_edu_wpi_first_hal_DIOJNI_getLoopTiming
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  jshort returnValue = HAL_GetPWMLoopTiming(&status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    allocateDigitalPWM
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DIOJNI_allocateDigitalPWM
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  auto pwm = HAL_AllocateDigitalPWM(&status);
+  CheckStatus(env, status);
+  return (jint)pwm;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    freeDigitalPWM
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_freeDigitalPWM
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_FreeDigitalPWM((HAL_DigitalPWMHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    setDigitalPWMRate
+ * Signature: (D)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_setDigitalPWMRate
+  (JNIEnv* env, jclass, jdouble value)
+{
+  int32_t status = 0;
+  HAL_SetDigitalPWMRate(value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    setDigitalPWMDutyCycle
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_setDigitalPWMDutyCycle
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  int32_t status = 0;
+  HAL_SetDigitalPWMDutyCycle((HAL_DigitalPWMHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    setDigitalPWMOutputChannel
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_setDigitalPWMOutputChannel
+  (JNIEnv* env, jclass, jint id, jint value)
+{
+  int32_t status = 0;
+  HAL_SetDigitalPWMOutputChannel((HAL_DigitalPWMHandle)id,
+                                 static_cast<uint32_t>(value), &status);
+  CheckStatus(env, status);
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/DigitalGlitchFilterJNI.cpp b/hal/src/main/native/cpp/jni/DigitalGlitchFilterJNI.cpp
new file mode 100644
index 0000000..fbbaadb
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/DigitalGlitchFilterJNI.cpp
@@ -0,0 +1,82 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_DigitalGlitchFilterJNI.h"
+#include "hal/DIO.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_DigitalGlitchFilterJNI
+ * Method:    setFilterSelect
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DigitalGlitchFilterJNI_setFilterSelect
+  (JNIEnv* env, jclass, jint id, jint filter_index)
+{
+  int32_t status = 0;
+
+  HAL_SetFilterSelect(static_cast<HAL_DigitalHandle>(id), filter_index,
+                      &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DigitalGlitchFilterJNI
+ * Method:    getFilterSelect
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DigitalGlitchFilterJNI_getFilterSelect
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+
+  jint result =
+      HAL_GetFilterSelect(static_cast<HAL_DigitalHandle>(id), &status);
+  CheckStatus(env, status);
+  return result;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DigitalGlitchFilterJNI
+ * Method:    setFilterPeriod
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DigitalGlitchFilterJNI_setFilterPeriod
+  (JNIEnv* env, jclass, jint filter_index, jint fpga_cycles)
+{
+  int32_t status = 0;
+
+  HAL_SetFilterPeriod(filter_index, fpga_cycles, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DigitalGlitchFilterJNI
+ * Method:    getFilterPeriod
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DigitalGlitchFilterJNI_getFilterPeriod
+  (JNIEnv* env, jclass, jint filter_index)
+{
+  int32_t status = 0;
+
+  jint result = HAL_GetFilterPeriod(filter_index, &status);
+  CheckStatus(env, status);
+  return result;
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/DutyCycleJNI.cpp b/hal/src/main/native/cpp/jni/DutyCycleJNI.cpp
new file mode 100644
index 0000000..510ca00
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/DutyCycleJNI.cpp
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <jni.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_DutyCycleJNI.h"
+#include "hal/DutyCycle.h"
+
+using namespace frc;
+
+extern "C" {
+/*
+ * Class:     edu_wpi_first_hal_DutyCycleJNI
+ * Method:    initialize
+ * Signature: (II)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DutyCycleJNI_initialize
+  (JNIEnv* env, jclass, jint digitalSourceHandle, jint analogTriggerType)
+{
+  int32_t status = 0;
+  auto handle = HAL_InitializeDutyCycle(
+      static_cast<HAL_Handle>(digitalSourceHandle),
+      static_cast<HAL_AnalogTriggerType>(analogTriggerType), &status);
+  CheckStatus(env, status);
+  return handle;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DutyCycleJNI
+ * Method:    free
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DutyCycleJNI_free
+  (JNIEnv*, jclass, jint handle)
+{
+  HAL_FreeDutyCycle(static_cast<HAL_DutyCycleHandle>(handle));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DutyCycleJNI
+ * Method:    getFrequency
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DutyCycleJNI_getFrequency
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  auto retVal = HAL_GetDutyCycleFrequency(
+      static_cast<HAL_DutyCycleHandle>(handle), &status);
+  CheckStatus(env, status);
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DutyCycleJNI
+ * Method:    getOutput
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_DutyCycleJNI_getOutput
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  auto retVal =
+      HAL_GetDutyCycleOutput(static_cast<HAL_DutyCycleHandle>(handle), &status);
+  CheckStatus(env, status);
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DutyCycleJNI
+ * Method:    getOutputRaw
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DutyCycleJNI_getOutputRaw
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  auto retVal = HAL_GetDutyCycleOutputRaw(
+      static_cast<HAL_DutyCycleHandle>(handle), &status);
+  CheckStatus(env, status);
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DutyCycleJNI
+ * Method:    getOutputScaleFactor
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DutyCycleJNI_getOutputScaleFactor
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  auto retVal = HAL_GetDutyCycleOutputScaleFactor(
+      static_cast<HAL_DutyCycleHandle>(handle), &status);
+  CheckStatus(env, status);
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DutyCycleJNI
+ * Method:    getFPGAIndex
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DutyCycleJNI_getFPGAIndex
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  auto retVal = HAL_GetDutyCycleFPGAIndex(
+      static_cast<HAL_DutyCycleHandle>(handle), &status);
+  CheckStatus(env, status);
+  return retVal;
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/EncoderJNI.cpp b/hal/src/main/native/cpp/jni/EncoderJNI.cpp
new file mode 100644
index 0000000..e5aa7e8
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/EncoderJNI.cpp
@@ -0,0 +1,392 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_EncoderJNI.h"
+#include "hal/Encoder.h"
+#include "hal/Errors.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    initializeEncoder
+ * Signature: (IIIIZI)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_initializeEncoder
+  (JNIEnv* env, jclass, jint digitalSourceHandleA, jint analogTriggerTypeA,
+   jint digitalSourceHandleB, jint analogTriggerTypeB,
+   jboolean reverseDirection, jint encodingType)
+{
+  int32_t status = 0;
+  auto encoder = HAL_InitializeEncoder(
+      (HAL_Handle)digitalSourceHandleA,
+      (HAL_AnalogTriggerType)analogTriggerTypeA,
+      (HAL_Handle)digitalSourceHandleB,
+      (HAL_AnalogTriggerType)analogTriggerTypeB, reverseDirection,
+      (HAL_EncoderEncodingType)encodingType, &status);
+  CheckStatusForceThrow(env, status);
+  return (jint)encoder;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    freeEncoder
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_freeEncoder
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_FreeEncoder((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    setEncoderSimDevice
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_setEncoderSimDevice
+  (JNIEnv* env, jclass, jint handle, jint device)
+{
+  HAL_SetEncoderSimDevice((HAL_EncoderHandle)handle,
+                          (HAL_SimDeviceHandle)device);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoder
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoder
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jint returnValue = HAL_GetEncoder((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderRaw
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderRaw
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jint returnValue = HAL_GetEncoderRaw((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncodingScaleFactor
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncodingScaleFactor
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetEncoderEncodingScale((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    resetEncoder
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_resetEncoder
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_ResetEncoder((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderPeriod
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderPeriod
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  double returnValue = HAL_GetEncoderPeriod((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    setEncoderMaxPeriod
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_setEncoderMaxPeriod
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  int32_t status = 0;
+  HAL_SetEncoderMaxPeriod((HAL_EncoderHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderStopped
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderStopped
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jboolean returnValue = HAL_GetEncoderStopped((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderDirection
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderDirection
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jboolean returnValue =
+      HAL_GetEncoderDirection((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderDistance
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderDistance
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jdouble returnValue = HAL_GetEncoderDistance((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderRate
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderRate
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jdouble returnValue = HAL_GetEncoderRate((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    setEncoderMinRate
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_setEncoderMinRate
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  int32_t status = 0;
+  HAL_SetEncoderMinRate((HAL_EncoderHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    setEncoderDistancePerPulse
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_setEncoderDistancePerPulse
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  int32_t status = 0;
+  HAL_SetEncoderDistancePerPulse((HAL_EncoderHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    setEncoderReverseDirection
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_setEncoderReverseDirection
+  (JNIEnv* env, jclass, jint id, jboolean value)
+{
+  int32_t status = 0;
+  HAL_SetEncoderReverseDirection((HAL_EncoderHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    setEncoderSamplesToAverage
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_setEncoderSamplesToAverage
+  (JNIEnv* env, jclass, jint id, jint value)
+{
+  int32_t status = 0;
+  HAL_SetEncoderSamplesToAverage((HAL_EncoderHandle)id, value, &status);
+  if (status == PARAMETER_OUT_OF_RANGE) {
+    ThrowBoundaryException(env, value, 1, 127);
+    return;
+  }
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderSamplesToAverage
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderSamplesToAverage
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetEncoderSamplesToAverage((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    setEncoderIndexSource
+ * Signature: (IIII)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_setEncoderIndexSource
+  (JNIEnv* env, jclass, jint id, jint digitalSourceHandle,
+   jint analogTriggerType, jint type)
+{
+  int32_t status = 0;
+  HAL_SetEncoderIndexSource((HAL_EncoderHandle)id,
+                            (HAL_Handle)digitalSourceHandle,
+                            (HAL_AnalogTriggerType)analogTriggerType,
+                            (HAL_EncoderIndexingType)type, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderFPGAIndex
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderFPGAIndex
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jint returnValue = HAL_GetEncoderFPGAIndex((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderEncodingScale
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderEncodingScale
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetEncoderEncodingScale((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderDecodingScaleFactor
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderDecodingScaleFactor
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jdouble returnValue =
+      HAL_GetEncoderDecodingScaleFactor((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderDistancePerPulse
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderDistancePerPulse
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jdouble returnValue =
+      HAL_GetEncoderDistancePerPulse((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderEncodingType
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderEncodingType
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jint returnValue = HAL_GetEncoderEncodingType((HAL_EncoderHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/HAL.cpp b/hal/src/main/native/cpp/jni/HAL.cpp
new file mode 100644
index 0000000..393b0b4
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/HAL.cpp
@@ -0,0 +1,477 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "hal/HAL.h"
+
+#include <jni.h>
+
+#include <cassert>
+#include <cstring>
+
+#include <wpi/jni_util.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_HAL.h"
+#include "hal/DriverStation.h"
+#include "hal/Main.h"
+
+using namespace frc;
+using namespace wpi::java;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    initialize
+ * Signature: (II)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_HAL_initialize
+  (JNIEnv*, jclass, jint timeout, jint mode)
+{
+  return HAL_Initialize(timeout, mode);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    hasMain
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_HAL_hasMain
+  (JNIEnv*, jclass)
+{
+  return HAL_HasMain();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    runMain
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_runMain
+  (JNIEnv*, jclass)
+{
+  HAL_RunMain();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    exitMain
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_exitMain
+  (JNIEnv*, jclass)
+{
+  HAL_ExitMain();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    observeUserProgramStarting
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_observeUserProgramStarting
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramStarting();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    observeUserProgramDisabled
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_observeUserProgramDisabled
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramDisabled();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    observeUserProgramAutonomous
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_observeUserProgramAutonomous
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramAutonomous();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    observeUserProgramTeleop
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_observeUserProgramTeleop
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramTeleop();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    observeUserProgramTest
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_observeUserProgramTest
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramTest();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    report
+ * Signature: (IIILjava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_report
+  (JNIEnv* paramEnv, jclass, jint paramResource, jint paramInstanceNumber,
+   jint paramContext, jstring paramFeature)
+{
+  JStringRef featureStr{paramEnv, paramFeature};
+  jint returnValue = HAL_Report(paramResource, paramInstanceNumber,
+                                paramContext, featureStr.c_str());
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    nativeGetControlWord
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_nativeGetControlWord
+  (JNIEnv*, jclass)
+{
+  static_assert(sizeof(HAL_ControlWord) == sizeof(jint),
+                "Java int must match the size of control word");
+  HAL_ControlWord controlWord;
+  std::memset(&controlWord, 0, sizeof(HAL_ControlWord));
+  HAL_GetControlWord(&controlWord);
+  jint retVal = 0;
+  std::memcpy(&retVal, &controlWord, sizeof(HAL_ControlWord));
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    nativeGetAllianceStation
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_nativeGetAllianceStation
+  (JNIEnv*, jclass)
+{
+  int32_t status = 0;
+  auto allianceStation = HAL_GetAllianceStation(&status);
+  return static_cast<jint>(allianceStation);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getJoystickAxes
+ * Signature: (B[F)S
+ */
+JNIEXPORT jshort JNICALL
+Java_edu_wpi_first_hal_HAL_getJoystickAxes
+  (JNIEnv* env, jclass, jbyte joystickNum, jfloatArray axesArray)
+{
+  HAL_JoystickAxes axes;
+  HAL_GetJoystickAxes(joystickNum, &axes);
+
+  jsize javaSize = env->GetArrayLength(axesArray);
+  if (axes.count > javaSize) {
+    wpi::SmallString<128> errStr;
+    wpi::raw_svector_ostream oss{errStr};
+    oss << "Native array size larger then passed in java array size "
+        << "Native Size: " << static_cast<int>(axes.count)
+        << " Java Size: " << static_cast<int>(javaSize);
+
+    ThrowIllegalArgumentException(env, errStr.str());
+    return 0;
+  }
+
+  env->SetFloatArrayRegion(axesArray, 0, axes.count, axes.axes);
+
+  return axes.count;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getJoystickPOVs
+ * Signature: (B[S)S
+ */
+JNIEXPORT jshort JNICALL
+Java_edu_wpi_first_hal_HAL_getJoystickPOVs
+  (JNIEnv* env, jclass, jbyte joystickNum, jshortArray povsArray)
+{
+  HAL_JoystickPOVs povs;
+  HAL_GetJoystickPOVs(joystickNum, &povs);
+
+  jsize javaSize = env->GetArrayLength(povsArray);
+  if (povs.count > javaSize) {
+    wpi::SmallString<128> errStr;
+    wpi::raw_svector_ostream oss{errStr};
+    oss << "Native array size larger then passed in java array size "
+        << "Native Size: " << static_cast<int>(povs.count)
+        << " Java Size: " << static_cast<int>(javaSize);
+
+    ThrowIllegalArgumentException(env, errStr.str());
+    return 0;
+  }
+
+  env->SetShortArrayRegion(povsArray, 0, povs.count, povs.povs);
+
+  return povs.count;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getJoystickButtons
+ * Signature: (BLjava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_getJoystickButtons
+  (JNIEnv* env, jclass, jbyte joystickNum, jobject count)
+{
+  HAL_JoystickButtons joystickButtons;
+  HAL_GetJoystickButtons(joystickNum, &joystickButtons);
+  jbyte* countPtr =
+      reinterpret_cast<jbyte*>(env->GetDirectBufferAddress(count));
+  *countPtr = joystickButtons.count;
+  return joystickButtons.buttons;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    setJoystickOutputs
+ * Signature: (BISS)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_setJoystickOutputs
+  (JNIEnv*, jclass, jbyte port, jint outputs, jshort leftRumble,
+   jshort rightRumble)
+{
+  return HAL_SetJoystickOutputs(port, outputs, leftRumble, rightRumble);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getJoystickIsXbox
+ * Signature: (B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_getJoystickIsXbox
+  (JNIEnv*, jclass, jbyte port)
+{
+  return HAL_GetJoystickIsXbox(port);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getJoystickType
+ * Signature: (B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_getJoystickType
+  (JNIEnv*, jclass, jbyte port)
+{
+  return HAL_GetJoystickType(port);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getJoystickName
+ * Signature: (B)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_hal_HAL_getJoystickName
+  (JNIEnv* env, jclass, jbyte port)
+{
+  char* joystickName = HAL_GetJoystickName(port);
+  jstring str = MakeJString(env, joystickName);
+  HAL_FreeJoystickName(joystickName);
+  return str;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getJoystickAxisType
+ * Signature: (BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_getJoystickAxisType
+  (JNIEnv*, jclass, jbyte joystickNum, jbyte axis)
+{
+  return HAL_GetJoystickAxisType(joystickNum, axis);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    isNewControlData
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_HAL_isNewControlData
+  (JNIEnv*, jclass)
+{
+  return static_cast<jboolean>(HAL_IsNewControlData());
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    waitForDSData
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_waitForDSData
+  (JNIEnv* env, jclass)
+{
+  HAL_WaitForDSData();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    releaseDSMutex
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_releaseDSMutex
+  (JNIEnv* env, jclass)
+{
+  HAL_ReleaseDSMutex();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    waitForDSDataTimeout
+ * Signature: (D)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_HAL_waitForDSDataTimeout
+  (JNIEnv*, jclass, jdouble timeout)
+{
+  return static_cast<jboolean>(HAL_WaitForDSDataTimeout(timeout));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getMatchTime
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_HAL_getMatchTime
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  return HAL_GetMatchTime(&status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getSystemActive
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_HAL_getSystemActive
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  bool val = HAL_GetSystemActive(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getBrownedOut
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_HAL_getBrownedOut
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  bool val = HAL_GetBrownedOut(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getMatchInfo
+ * Signature: (Ljava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_getMatchInfo
+  (JNIEnv* env, jclass, jobject info)
+{
+  HAL_MatchInfo matchInfo;
+  auto status = HAL_GetMatchInfo(&matchInfo);
+  if (status == 0) {
+    SetMatchInfoObject(env, info, matchInfo);
+  }
+  return status;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    sendError
+ * Signature: (ZIZLjava/lang/String;Ljava/lang/String;Ljava/lang/String;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_sendError
+  (JNIEnv* env, jclass, jboolean isError, jint errorCode, jboolean isLVCode,
+   jstring details, jstring location, jstring callStack, jboolean printMsg)
+{
+  JStringRef detailsStr{env, details};
+  JStringRef locationStr{env, location};
+  JStringRef callStackStr{env, callStack};
+
+  jint returnValue =
+      HAL_SendError(isError, errorCode, isLVCode, detailsStr.c_str(),
+                    locationStr.c_str(), callStackStr.c_str(), printMsg);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getPortWithModule
+ * Signature: (BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_getPortWithModule
+  (JNIEnv* env, jclass, jbyte module, jbyte channel)
+{
+  HAL_PortHandle port = HAL_GetPortWithModule(module, channel);
+  return (jint)port;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getPort
+ * Signature: (B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_getPort
+  (JNIEnv* env, jclass, jbyte channel)
+{
+  HAL_PortHandle port = HAL_GetPort(channel);
+  return (jint)port;
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/HALUtil.cpp b/hal/src/main/native/cpp/jni/HALUtil.cpp
new file mode 100644
index 0000000..26b7919
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/HALUtil.cpp
@@ -0,0 +1,469 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "HALUtil.h"
+
+#include <jni.h>
+
+#include <cassert>
+#include <cerrno>
+#include <cstdio>
+#include <cstring>
+#include <string>
+
+#include <wpi/SmallString.h>
+#include <wpi/jni_util.h>
+#include <wpi/raw_ostream.h>
+
+#include "edu_wpi_first_hal_HALUtil.h"
+#include "hal/CAN.h"
+#include "hal/DriverStation.h"
+#include "hal/Errors.h"
+#include "hal/HAL.h"
+
+using namespace wpi::java;
+
+#define kRioStatusOffset -63000
+#define kRioStatusSuccess 0
+#define kRIOStatusBufferInvalidSize (kRioStatusOffset - 80)
+#define kRIOStatusOperationTimedOut -52007
+#define kRIOStatusFeatureNotSupported (kRioStatusOffset - 193)
+#define kRIOStatusResourceNotInitialized -52010
+
+static JavaVM* jvm = nullptr;
+static JException illegalArgExCls;
+static JException boundaryExCls;
+static JException allocationExCls;
+static JException halHandleExCls;
+static JException canInvalidBufferExCls;
+static JException canMessageNotFoundExCls;
+static JException canMessageNotAllowedExCls;
+static JException canNotInitializedExCls;
+static JException uncleanStatusExCls;
+static JClass pwmConfigDataResultCls;
+static JClass canStatusCls;
+static JClass matchInfoDataCls;
+static JClass accumulatorResultCls;
+static JClass canDataCls;
+static JClass halValueCls;
+
+static const JClassInit classes[] = {
+    {"edu/wpi/first/hal/PWMConfigDataResult", &pwmConfigDataResultCls},
+    {"edu/wpi/first/hal/can/CANStatus", &canStatusCls},
+    {"edu/wpi/first/hal/MatchInfoData", &matchInfoDataCls},
+    {"edu/wpi/first/hal/AccumulatorResult", &accumulatorResultCls},
+    {"edu/wpi/first/hal/CANData", &canDataCls},
+    {"edu/wpi/first/hal/HALValue", &halValueCls}};
+
+static const JExceptionInit exceptions[] = {
+    {"java/lang/IllegalArgumentException", &illegalArgExCls},
+    {"edu/wpi/first/hal/util/BoundaryException", &boundaryExCls},
+    {"edu/wpi/first/hal/util/AllocationException", &allocationExCls},
+    {"edu/wpi/first/hal/util/HalHandleException", &halHandleExCls},
+    {"edu/wpi/first/hal/can/CANInvalidBufferException", &canInvalidBufferExCls},
+    {"edu/wpi/first/hal/can/CANMessageNotFoundException",
+     &canMessageNotFoundExCls},
+    {"edu/wpi/first/hal/can/CANMessageNotAllowedException",
+     &canMessageNotAllowedExCls},
+    {"edu/wpi/first/hal/can/CANNotInitializedException",
+     &canNotInitializedExCls},
+    {"edu/wpi/first/hal/util/UncleanStatusException", &uncleanStatusExCls}};
+
+namespace frc {
+
+void ThrowUncleanStatusException(JNIEnv* env, wpi::StringRef msg,
+                                 int32_t status) {
+  static jmethodID func =
+      env->GetMethodID(uncleanStatusExCls, "<init>", "(ILjava/lang/String;)V");
+
+  jobject exception =
+      env->NewObject(uncleanStatusExCls, func, static_cast<jint>(status),
+                     MakeJString(env, msg));
+  env->Throw(static_cast<jthrowable>(exception));
+}
+
+void ThrowAllocationException(JNIEnv* env, int32_t minRange, int32_t maxRange,
+                              int32_t requestedValue, int32_t status) {
+  const char* message = HAL_GetErrorMessage(status);
+  wpi::SmallString<1024> buf;
+  wpi::raw_svector_ostream oss(buf);
+  oss << " Code: " << status << ". " << message
+      << ", Minimum Value: " << minRange << ", Maximum Value: " << maxRange
+      << ", Requested Value: " << requestedValue;
+  env->ThrowNew(allocationExCls, buf.c_str());
+  allocationExCls.Throw(env, buf.c_str());
+}
+
+void ThrowHalHandleException(JNIEnv* env, int32_t status) {
+  const char* message = HAL_GetErrorMessage(status);
+  wpi::SmallString<1024> buf;
+  wpi::raw_svector_ostream oss(buf);
+  oss << " Code: " << status << ". " << message;
+  halHandleExCls.Throw(env, buf.c_str());
+}
+
+void ReportError(JNIEnv* env, int32_t status, bool doThrow) {
+  if (status == 0) return;
+  if (status == HAL_HANDLE_ERROR) {
+    ThrowHalHandleException(env, status);
+  }
+  const char* message = HAL_GetErrorMessage(status);
+  if (doThrow && status < 0) {
+    wpi::SmallString<1024> buf;
+    wpi::raw_svector_ostream oss(buf);
+    oss << " Code: " << status << ". " << message;
+    ThrowUncleanStatusException(env, buf.c_str(), status);
+  } else {
+    std::string func;
+    auto stack = GetJavaStackTrace(env, &func, "edu.wpi.first");
+    HAL_SendError(1, status, 0, message, func.c_str(), stack.c_str(), 1);
+  }
+}
+
+void ThrowError(JNIEnv* env, int32_t status, int32_t minRange, int32_t maxRange,
+                int32_t requestedValue) {
+  if (status == 0) return;
+  if (status == NO_AVAILABLE_RESOURCES || status == RESOURCE_IS_ALLOCATED ||
+      status == RESOURCE_OUT_OF_RANGE) {
+    ThrowAllocationException(env, minRange, maxRange, requestedValue, status);
+  }
+  if (status == HAL_HANDLE_ERROR) {
+    ThrowHalHandleException(env, status);
+  }
+  const char* message = HAL_GetErrorMessage(status);
+  wpi::SmallString<1024> buf;
+  wpi::raw_svector_ostream oss(buf);
+  oss << " Code: " << status << ". " << message;
+  ThrowUncleanStatusException(env, buf.c_str(), status);
+}
+
+void ReportCANError(JNIEnv* env, int32_t status, int message_id) {
+  if (status >= 0) return;
+  switch (status) {
+    case kRioStatusSuccess:
+      // Everything is ok... don't throw.
+      break;
+    case HAL_ERR_CANSessionMux_InvalidBuffer:
+    case kRIOStatusBufferInvalidSize: {
+      static jmethodID invalidBufConstruct = nullptr;
+      if (!invalidBufConstruct)
+        invalidBufConstruct =
+            env->GetMethodID(canInvalidBufferExCls, "<init>", "()V");
+      jobject exception =
+          env->NewObject(canInvalidBufferExCls, invalidBufConstruct);
+      env->Throw(static_cast<jthrowable>(exception));
+      break;
+    }
+    case HAL_ERR_CANSessionMux_MessageNotFound:
+    case kRIOStatusOperationTimedOut: {
+      static jmethodID messageNotFoundConstruct = nullptr;
+      if (!messageNotFoundConstruct)
+        messageNotFoundConstruct =
+            env->GetMethodID(canMessageNotFoundExCls, "<init>", "()V");
+      jobject exception =
+          env->NewObject(canMessageNotFoundExCls, messageNotFoundConstruct);
+      env->Throw(static_cast<jthrowable>(exception));
+      break;
+    }
+    case HAL_ERR_CANSessionMux_NotAllowed:
+    case kRIOStatusFeatureNotSupported: {
+      wpi::SmallString<100> buf;
+      wpi::raw_svector_ostream oss(buf);
+      oss << "MessageID = " << message_id;
+      canMessageNotAllowedExCls.Throw(env, buf.c_str());
+      break;
+    }
+    case HAL_ERR_CANSessionMux_NotInitialized:
+    case kRIOStatusResourceNotInitialized: {
+      static jmethodID notInitConstruct = nullptr;
+      if (!notInitConstruct)
+        notInitConstruct =
+            env->GetMethodID(canNotInitializedExCls, "<init>", "()V");
+      jobject exception =
+          env->NewObject(canNotInitializedExCls, notInitConstruct);
+      env->Throw(static_cast<jthrowable>(exception));
+      break;
+    }
+    default: {
+      wpi::SmallString<100> buf;
+      wpi::raw_svector_ostream oss(buf);
+      oss << "Fatal status code detected: " << status;
+      uncleanStatusExCls.Throw(env, buf.c_str());
+      break;
+    }
+  }
+}
+
+void ThrowIllegalArgumentException(JNIEnv* env, wpi::StringRef msg) {
+  illegalArgExCls.Throw(env, msg);
+}
+
+void ThrowBoundaryException(JNIEnv* env, double value, double lower,
+                            double upper) {
+  static jmethodID getMessage = nullptr;
+  if (!getMessage)
+    getMessage = env->GetStaticMethodID(boundaryExCls, "getMessage",
+                                        "(DDD)Ljava/lang/String;");
+
+  static jmethodID constructor = nullptr;
+  if (!constructor)
+    constructor =
+        env->GetMethodID(boundaryExCls, "<init>", "(Ljava/lang/String;)V");
+
+  jobject msg = env->CallStaticObjectMethod(
+      boundaryExCls, getMessage, static_cast<jdouble>(value),
+      static_cast<jdouble>(lower), static_cast<jdouble>(upper));
+  jobject ex = env->NewObject(boundaryExCls, constructor, msg);
+  env->Throw(static_cast<jthrowable>(ex));
+}
+
+jobject CreatePWMConfigDataResult(JNIEnv* env, int32_t maxPwm,
+                                  int32_t deadbandMaxPwm, int32_t centerPwm,
+                                  int32_t deadbandMinPwm, int32_t minPwm) {
+  static jmethodID constructor =
+      env->GetMethodID(pwmConfigDataResultCls, "<init>", "(IIIII)V");
+  return env->NewObject(pwmConfigDataResultCls, constructor, (jint)maxPwm,
+                        (jint)deadbandMaxPwm, (jint)centerPwm,
+                        (jint)deadbandMinPwm, (jint)minPwm);
+}
+
+void SetCanStatusObject(JNIEnv* env, jobject canStatus,
+                        float percentBusUtilization, uint32_t busOffCount,
+                        uint32_t txFullCount, uint32_t receiveErrorCount,
+                        uint32_t transmitErrorCount) {
+  static jmethodID func =
+      env->GetMethodID(canStatusCls, "setStatus", "(DIIII)V");
+  env->CallVoidMethod(canStatus, func, (jdouble)percentBusUtilization,
+                      (jint)busOffCount, (jint)txFullCount,
+                      (jint)receiveErrorCount, (jint)transmitErrorCount);
+}
+
+void SetMatchInfoObject(JNIEnv* env, jobject matchStatus,
+                        const HAL_MatchInfo& matchInfo) {
+  static jmethodID func =
+      env->GetMethodID(matchInfoDataCls, "setData",
+                       "(Ljava/lang/String;Ljava/lang/String;III)V");
+
+  env->CallVoidMethod(
+      matchStatus, func, MakeJString(env, matchInfo.eventName),
+      MakeJString(env, wpi::StringRef{reinterpret_cast<const char*>(
+                                          matchInfo.gameSpecificMessage),
+                                      matchInfo.gameSpecificMessageSize}),
+      (jint)matchInfo.matchNumber, (jint)matchInfo.replayNumber,
+      (jint)matchInfo.matchType);
+}
+
+void SetAccumulatorResultObject(JNIEnv* env, jobject accumulatorResult,
+                                int64_t value, int64_t count) {
+  static jmethodID func =
+      env->GetMethodID(accumulatorResultCls, "set", "(JJ)V");
+
+  env->CallVoidMethod(accumulatorResult, func, (jlong)value, (jlong)count);
+}
+
+jbyteArray SetCANDataObject(JNIEnv* env, jobject canData, int32_t length,
+                            uint64_t timestamp) {
+  static jmethodID func = env->GetMethodID(canDataCls, "setData", "(IJ)[B");
+
+  jbyteArray retVal = static_cast<jbyteArray>(
+      env->CallObjectMethod(canData, func, (jint)length, (jlong)timestamp));
+  return retVal;
+}
+
+jobject CreateHALValue(JNIEnv* env, const HAL_Value& value) {
+  static jmethodID fromNative = env->GetStaticMethodID(
+      halValueCls, "fromNative", "(IJD)Ledu/wpi/first/hal/HALValue;");
+  jlong value1 = 0;
+  jdouble value2 = 0.0;
+  switch (value.type) {
+    case HAL_BOOLEAN:
+      value1 = value.data.v_boolean;
+      break;
+    case HAL_DOUBLE:
+      value2 = value.data.v_double;
+      break;
+    case HAL_ENUM:
+      value1 = value.data.v_enum;
+      break;
+    case HAL_INT:
+      value1 = value.data.v_int;
+      break;
+    case HAL_LONG:
+      value1 = value.data.v_long;
+      break;
+    default:
+      break;
+  }
+  return env->CallStaticObjectMethod(halValueCls, fromNative, (jint)value.type,
+                                     value1, value2);
+}
+
+JavaVM* GetJVM() { return jvm; }
+
+}  // namespace frc
+
+namespace sim {
+jint SimOnLoad(JavaVM* vm, void* reserved);
+void SimOnUnload(JavaVM* vm, void* reserved);
+}  // namespace sim
+
+using namespace frc;
+
+extern "C" {
+
+//
+// indicate JNI version support desired and load classes
+//
+JNIEXPORT jint JNICALL JNI_OnLoad(JavaVM* vm, void* reserved) {
+  jvm = vm;
+
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK)
+    return JNI_ERR;
+
+  for (auto& c : classes) {
+    *c.cls = JClass(env, c.name);
+    if (!*c.cls) return JNI_ERR;
+  }
+
+  for (auto& c : exceptions) {
+    *c.cls = JException(env, c.name);
+    if (!*c.cls) return JNI_ERR;
+  }
+
+  return sim::SimOnLoad(vm, reserved);
+}
+
+JNIEXPORT void JNICALL JNI_OnUnload(JavaVM* vm, void* reserved) {
+  sim::SimOnUnload(vm, reserved);
+
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK)
+    return;
+  // Delete global references
+
+  for (auto& c : classes) {
+    c.cls->free(env);
+  }
+  for (auto& c : exceptions) {
+    c.cls->free(env);
+  }
+  jvm = nullptr;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getFPGAVersion
+ * Signature: ()S
+ */
+JNIEXPORT jshort JNICALL
+Java_edu_wpi_first_hal_HALUtil_getFPGAVersion
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  jshort returnValue = HAL_GetFPGAVersion(&status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getFPGARevision
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HALUtil_getFPGARevision
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  jint returnValue = HAL_GetFPGARevision(&status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getFPGATime
+ * Signature: ()J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_hal_HALUtil_getFPGATime
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  jlong returnValue = HAL_GetFPGATime(&status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getHALRuntimeType
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HALUtil_getHALRuntimeType
+  (JNIEnv* env, jclass)
+{
+  jint returnValue = HAL_GetRuntimeType();
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getFPGAButton
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_HALUtil_getFPGAButton
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  jboolean returnValue = HAL_GetFPGAButton(&status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getHALErrorMessage
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_hal_HALUtil_getHALErrorMessage
+  (JNIEnv* paramEnv, jclass, jint paramId)
+{
+  const char* msg = HAL_GetErrorMessage(paramId);
+  return MakeJString(paramEnv, msg);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getHALErrno
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HALUtil_getHALErrno
+  (JNIEnv*, jclass)
+{
+  return errno;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getHALstrerror
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_hal_HALUtil_getHALstrerror
+  (JNIEnv* env, jclass, jint errorCode)
+{
+  const char* msg = std::strerror(errno);
+  return MakeJString(env, msg);
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/HALUtil.h b/hal/src/main/native/cpp/jni/HALUtil.h
new file mode 100644
index 0000000..c035f75
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/HALUtil.h
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef HAL_HAL_SRC_MAIN_NATIVE_CPP_JNI_HALUTIL_H_
+#define HAL_HAL_SRC_MAIN_NATIVE_CPP_JNI_HALUTIL_H_
+
+#include <jni.h>
+#include <stdint.h>
+
+#include <wpi/StringRef.h>
+
+struct HAL_MatchInfo;
+struct HAL_Value;
+
+namespace frc {
+
+void ReportError(JNIEnv* env, int32_t status, bool doThrow = true);
+
+void ThrowError(JNIEnv* env, int32_t status, int32_t minRange, int32_t maxRange,
+                int32_t requestedValue);
+
+inline bool CheckStatus(JNIEnv* env, int32_t status, bool doThrow = true) {
+  if (status != 0) ReportError(env, status, doThrow);
+  return status == 0;
+}
+
+inline bool CheckStatusRange(JNIEnv* env, int32_t status, int32_t minRange,
+                             int32_t maxRange, int32_t requestedValue) {
+  if (status != 0) ThrowError(env, status, minRange, maxRange, requestedValue);
+  return status == 0;
+}
+
+inline bool CheckStatusForceThrow(JNIEnv* env, int32_t status) {
+  if (status != 0) ThrowError(env, status, 0, 0, 0);
+  return status == 0;
+}
+
+void ReportCANError(JNIEnv* env, int32_t status, int32_t message_id);
+
+inline bool CheckCANStatus(JNIEnv* env, int32_t status, int32_t message_id) {
+  if (status != 0) ReportCANError(env, status, message_id);
+  return status == 0;
+}
+
+void ThrowIllegalArgumentException(JNIEnv* env, wpi::StringRef msg);
+void ThrowBoundaryException(JNIEnv* env, double value, double lower,
+                            double upper);
+
+jobject CreatePWMConfigDataResult(JNIEnv* env, int32_t maxPwm,
+                                  int32_t deadbandMaxPwm, int32_t centerPwm,
+                                  int32_t deadbandMinPwm, int32_t minPwm);
+
+void SetCanStatusObject(JNIEnv* env, jobject canStatus,
+                        float percentBusUtilization, uint32_t busOffCount,
+                        uint32_t txFullCount, uint32_t receiveErrorCount,
+                        uint32_t transmitErrorCount);
+
+void SetMatchInfoObject(JNIEnv* env, jobject matchStatus,
+                        const HAL_MatchInfo& matchInfo);
+
+void SetAccumulatorResultObject(JNIEnv* env, jobject accumulatorResult,
+                                int64_t value, int64_t count);
+
+jbyteArray SetCANDataObject(JNIEnv* env, jobject canData, int32_t length,
+                            uint64_t timestamp);
+
+jobject CreateHALValue(JNIEnv* env, const HAL_Value& value);
+
+JavaVM* GetJVM();
+
+}  // namespace frc
+
+#endif  // HAL_HAL_SRC_MAIN_NATIVE_CPP_JNI_HALUTIL_H_
diff --git a/hal/src/main/native/cpp/jni/I2CJNI.cpp b/hal/src/main/native/cpp/jni/I2CJNI.cpp
new file mode 100644
index 0000000..7812bdb
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/I2CJNI.cpp
@@ -0,0 +1,169 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include <wpi/jni_util.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_I2CJNI.h"
+#include "hal/I2C.h"
+
+using namespace frc;
+using namespace wpi::java;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CInitialize
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CInitialize
+  (JNIEnv* env, jclass, jint port)
+{
+  int32_t status = 0;
+  HAL_InitializeI2C(static_cast<HAL_I2CPort>(port), &status);
+  CheckStatusForceThrow(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CTransaction
+ * Signature: (IBLjava/lang/Object;BLjava/lang/Object;B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CTransaction
+  (JNIEnv* env, jclass, jint port, jbyte address, jobject dataToSend,
+   jbyte sendSize, jobject dataReceived, jbyte receiveSize)
+{
+  uint8_t* dataToSendPtr = nullptr;
+  if (dataToSend != 0) {
+    dataToSendPtr =
+        reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataToSend));
+  }
+  uint8_t* dataReceivedPtr =
+      reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataReceived));
+  jint returnValue =
+      HAL_TransactionI2C(static_cast<HAL_I2CPort>(port), address, dataToSendPtr,
+                         sendSize, dataReceivedPtr, receiveSize);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CTransactionB
+ * Signature: (IB[BB[BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CTransactionB
+  (JNIEnv* env, jclass, jint port, jbyte address, jbyteArray dataToSend,
+   jbyte sendSize, jbyteArray dataReceived, jbyte receiveSize)
+{
+  wpi::SmallVector<uint8_t, 128> recvBuf;
+  recvBuf.resize(receiveSize);
+  jint returnValue =
+      HAL_TransactionI2C(static_cast<HAL_I2CPort>(port), address,
+                         reinterpret_cast<const uint8_t*>(
+                             JByteArrayRef(env, dataToSend).array().data()),
+                         sendSize, recvBuf.data(), receiveSize);
+  env->SetByteArrayRegion(dataReceived, 0, receiveSize,
+                          reinterpret_cast<const jbyte*>(recvBuf.data()));
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CWrite
+ * Signature: (IBLjava/lang/Object;B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CWrite
+  (JNIEnv* env, jclass, jint port, jbyte address, jobject dataToSend,
+   jbyte sendSize)
+{
+  uint8_t* dataToSendPtr = nullptr;
+
+  if (dataToSend != 0) {
+    dataToSendPtr =
+        reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataToSend));
+  }
+  jint returnValue = HAL_WriteI2C(static_cast<HAL_I2CPort>(port), address,
+                                  dataToSendPtr, sendSize);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CWriteB
+ * Signature: (IB[BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CWriteB
+  (JNIEnv* env, jclass, jint port, jbyte address, jbyteArray dataToSend,
+   jbyte sendSize)
+{
+  jint returnValue =
+      HAL_WriteI2C(static_cast<HAL_I2CPort>(port), address,
+                   reinterpret_cast<const uint8_t*>(
+                       JByteArrayRef(env, dataToSend).array().data()),
+                   sendSize);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CRead
+ * Signature: (IBLjava/lang/Object;B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CRead
+  (JNIEnv* env, jclass, jint port, jbyte address, jobject dataReceived,
+   jbyte receiveSize)
+{
+  uint8_t* dataReceivedPtr =
+      reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataReceived));
+  jint returnValue = HAL_ReadI2C(static_cast<HAL_I2CPort>(port), address,
+                                 dataReceivedPtr, receiveSize);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CReadB
+ * Signature: (IB[BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CReadB
+  (JNIEnv* env, jclass, jint port, jbyte address, jbyteArray dataReceived,
+   jbyte receiveSize)
+{
+  wpi::SmallVector<uint8_t, 128> recvBuf;
+  recvBuf.resize(receiveSize);
+  jint returnValue = HAL_ReadI2C(static_cast<HAL_I2CPort>(port), address,
+                                 recvBuf.data(), receiveSize);
+  env->SetByteArrayRegion(dataReceived, 0, receiveSize,
+                          reinterpret_cast<const jbyte*>(recvBuf.data()));
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CClose
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CClose
+  (JNIEnv*, jclass, jint port)
+{
+  HAL_CloseI2C(static_cast<HAL_I2CPort>(port));
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/InterruptJNI.cpp b/hal/src/main/native/cpp/jni/InterruptJNI.cpp
new file mode 100644
index 0000000..e3a783d
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/InterruptJNI.cpp
@@ -0,0 +1,297 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <atomic>
+#include <cassert>
+#include <thread>
+
+#include <wpi/SafeThread.h>
+#include <wpi/mutex.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_InterruptJNI.h"
+#include "hal/Interrupts.h"
+
+using namespace frc;
+
+// Thread where callbacks are actually performed.
+//
+// JNI's AttachCurrentThread() creates a Java Thread object on every
+// invocation, which is both time inefficient and causes issues with Eclipse
+// (which tries to keep a thread list up-to-date and thus gets swamped).
+//
+// Instead, this class attaches just once.  When a hardware notification
+// occurs, a condition variable wakes up this thread and this thread actually
+// makes the call into Java.
+//
+// We don't want to use a FIFO here. If the user code takes too long to
+// process, we will just ignore the redundant wakeup.
+class InterruptThreadJNI : public wpi::SafeThread {
+ public:
+  void Main();
+
+  bool m_notify = false;
+  uint32_t m_mask = 0;
+  jobject m_func = nullptr;
+  jmethodID m_mid;
+  jobject m_param = nullptr;
+};
+
+class InterruptJNI : public wpi::SafeThreadOwner<InterruptThreadJNI> {
+ public:
+  void SetFunc(JNIEnv* env, jobject func, jmethodID mid, jobject param);
+
+  void Notify(uint32_t mask) {
+    auto thr = GetThread();
+    if (!thr) return;
+    thr->m_notify = true;
+    thr->m_mask = mask;
+    thr->m_cond.notify_one();
+  }
+};
+
+void InterruptJNI::SetFunc(JNIEnv* env, jobject func, jmethodID mid,
+                           jobject param) {
+  auto thr = GetThread();
+  if (!thr) return;
+  // free global references
+  if (thr->m_func) env->DeleteGlobalRef(thr->m_func);
+  if (thr->m_param) env->DeleteGlobalRef(thr->m_param);
+  // create global references
+  thr->m_func = env->NewGlobalRef(func);
+  thr->m_param = param ? env->NewGlobalRef(param) : nullptr;
+  thr->m_mid = mid;
+}
+
+void InterruptThreadJNI::Main() {
+  JNIEnv* env;
+  JavaVMAttachArgs args;
+  args.version = JNI_VERSION_1_2;
+  args.name = const_cast<char*>("Interrupt");
+  args.group = nullptr;
+  jint rs = GetJVM()->AttachCurrentThreadAsDaemon(
+      reinterpret_cast<void**>(&env), &args);
+  if (rs != JNI_OK) return;
+
+  std::unique_lock lock(m_mutex);
+  while (m_active) {
+    m_cond.wait(lock, [&] { return !m_active || m_notify; });
+    if (!m_active) break;
+    m_notify = false;
+    if (!m_func) continue;
+    jobject func = m_func;
+    jmethodID mid = m_mid;
+    uint32_t mask = m_mask;
+    jobject param = m_param;
+    lock.unlock();  // don't hold mutex during callback execution
+    env->CallVoidMethod(func, mid, static_cast<jint>(mask), param);
+    if (env->ExceptionCheck()) {
+      env->ExceptionDescribe();
+      env->ExceptionClear();
+    }
+    lock.lock();
+  }
+
+  // free global references
+  if (m_func) env->DeleteGlobalRef(m_func);
+  if (m_param) env->DeleteGlobalRef(m_param);
+
+  GetJVM()->DetachCurrentThread();
+}
+
+void interruptHandler(uint32_t mask, void* param) {
+  static_cast<InterruptJNI*>(param)->Notify(mask);
+}
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    initializeInterrupts
+ * Signature: (Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_initializeInterrupts
+  (JNIEnv* env, jclass, jboolean watcher)
+{
+  int32_t status = 0;
+  HAL_InterruptHandle interrupt = HAL_InitializeInterrupts(watcher, &status);
+
+  CheckStatusForceThrow(env, status);
+  return (jint)interrupt;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    cleanInterrupts
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_cleanInterrupts
+  (JNIEnv* env, jclass, jint interruptHandle)
+{
+  int32_t status = 0;
+  auto param =
+      HAL_CleanInterrupts((HAL_InterruptHandle)interruptHandle, &status);
+  if (param) {
+    delete static_cast<InterruptJNI*>(param);
+  }
+
+  // ignore status, as an invalid handle just needs to be ignored.
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    waitForInterrupt
+ * Signature: (IDZ)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_waitForInterrupt
+  (JNIEnv* env, jclass, jint interruptHandle, jdouble timeout,
+   jboolean ignorePrevious)
+{
+  int32_t status = 0;
+  int32_t result = HAL_WaitForInterrupt((HAL_InterruptHandle)interruptHandle,
+                                        timeout, ignorePrevious, &status);
+
+  CheckStatus(env, status);
+  return result;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    enableInterrupts
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_enableInterrupts
+  (JNIEnv* env, jclass, jint interruptHandle)
+{
+  int32_t status = 0;
+  HAL_EnableInterrupts((HAL_InterruptHandle)interruptHandle, &status);
+
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    disableInterrupts
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_disableInterrupts
+  (JNIEnv* env, jclass, jint interruptHandle)
+{
+  int32_t status = 0;
+  HAL_DisableInterrupts((HAL_InterruptHandle)interruptHandle, &status);
+
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    readInterruptRisingTimestamp
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_readInterruptRisingTimestamp
+  (JNIEnv* env, jclass, jint interruptHandle)
+{
+  int32_t status = 0;
+  jlong timeStamp = HAL_ReadInterruptRisingTimestamp(
+      (HAL_InterruptHandle)interruptHandle, &status);
+
+  CheckStatus(env, status);
+  return timeStamp;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    readInterruptFallingTimestamp
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_readInterruptFallingTimestamp
+  (JNIEnv* env, jclass, jint interruptHandle)
+{
+  int32_t status = 0;
+  jlong timeStamp = HAL_ReadInterruptFallingTimestamp(
+      (HAL_InterruptHandle)interruptHandle, &status);
+
+  CheckStatus(env, status);
+  return timeStamp;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    requestInterrupts
+ * Signature: (III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_requestInterrupts
+  (JNIEnv* env, jclass, jint interruptHandle, jint digitalSourceHandle,
+   jint analogTriggerType)
+{
+  int32_t status = 0;
+  HAL_RequestInterrupts((HAL_InterruptHandle)interruptHandle,
+                        (HAL_Handle)digitalSourceHandle,
+                        (HAL_AnalogTriggerType)analogTriggerType, &status);
+
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    attachInterruptHandler
+ * Signature: (ILjava/lang/Object;Ljava/lang/Object;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_attachInterruptHandler
+  (JNIEnv* env, jclass, jint interruptHandle, jobject handler, jobject param)
+{
+  jclass cls = env->GetObjectClass(handler);
+  if (cls == 0) {
+    assert(false);
+    return;
+  }
+  jmethodID mid = env->GetMethodID(cls, "apply", "(ILjava/lang/Object;)V");
+  if (mid == 0) {
+    assert(false);
+    return;
+  }
+
+  InterruptJNI* intr = new InterruptJNI;
+  intr->Start();
+  intr->SetFunc(env, handler, mid, param);
+
+  int32_t status = 0;
+  HAL_AttachInterruptHandler((HAL_InterruptHandle)interruptHandle,
+                             interruptHandler, intr, &status);
+
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    setInterruptUpSourceEdge
+ * Signature: (IZZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_setInterruptUpSourceEdge
+  (JNIEnv* env, jclass, jint interruptHandle, jboolean risingEdge,
+   jboolean fallingEdge)
+{
+  int32_t status = 0;
+  HAL_SetInterruptUpSourceEdge((HAL_InterruptHandle)interruptHandle, risingEdge,
+                               fallingEdge, &status);
+
+  CheckStatus(env, status);
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/NotifierJNI.cpp b/hal/src/main/native/cpp/jni/NotifierJNI.cpp
new file mode 100644
index 0000000..874d750
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/NotifierJNI.cpp
@@ -0,0 +1,132 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+#include <cstdio>
+
+#include <wpi/jni_util.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_NotifierJNI.h"
+#include "hal/Notifier.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_NotifierJNI
+ * Method:    initializeNotifier
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_NotifierJNI_initializeNotifier
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  HAL_NotifierHandle notifierHandle = HAL_InitializeNotifier(&status);
+
+  if (notifierHandle <= 0 || !CheckStatusForceThrow(env, status)) {
+    return 0;  // something went wrong in HAL
+  }
+
+  return (jint)notifierHandle;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_NotifierJNI
+ * Method:    setNotifierName
+ * Signature: (ILjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_NotifierJNI_setNotifierName
+  (JNIEnv* env, jclass cls, jint notifierHandle, jstring name)
+{
+  int32_t status = 0;
+  HAL_SetNotifierName((HAL_NotifierHandle)notifierHandle,
+                      wpi::java::JStringRef{env, name}.c_str(), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_NotifierJNI
+ * Method:    stopNotifier
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_NotifierJNI_stopNotifier
+  (JNIEnv* env, jclass cls, jint notifierHandle)
+{
+  int32_t status = 0;
+  HAL_StopNotifier((HAL_NotifierHandle)notifierHandle, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_NotifierJNI
+ * Method:    cleanNotifier
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_NotifierJNI_cleanNotifier
+  (JNIEnv* env, jclass, jint notifierHandle)
+{
+  int32_t status = 0;
+  HAL_CleanNotifier((HAL_NotifierHandle)notifierHandle, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_NotifierJNI
+ * Method:    updateNotifierAlarm
+ * Signature: (IJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_NotifierJNI_updateNotifierAlarm
+  (JNIEnv* env, jclass cls, jint notifierHandle, jlong triggerTime)
+{
+  int32_t status = 0;
+  HAL_UpdateNotifierAlarm((HAL_NotifierHandle)notifierHandle,
+                          static_cast<uint64_t>(triggerTime), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_NotifierJNI
+ * Method:    cancelNotifierAlarm
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_NotifierJNI_cancelNotifierAlarm
+  (JNIEnv* env, jclass cls, jint notifierHandle)
+{
+  int32_t status = 0;
+  HAL_CancelNotifierAlarm((HAL_NotifierHandle)notifierHandle, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_NotifierJNI
+ * Method:    waitForNotifierAlarm
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_hal_NotifierJNI_waitForNotifierAlarm
+  (JNIEnv* env, jclass cls, jint notifierHandle)
+{
+  int32_t status = 0;
+  uint64_t time =
+      HAL_WaitForNotifierAlarm((HAL_NotifierHandle)notifierHandle, &status);
+
+  CheckStatus(env, status);
+
+  return (jlong)time;
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/PDPJNI.cpp b/hal/src/main/native/cpp/jni/PDPJNI.cpp
new file mode 100644
index 0000000..f649a8d
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/PDPJNI.cpp
@@ -0,0 +1,193 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "HALUtil.h"
+#include "edu_wpi_first_hal_PDPJNI.h"
+#include "hal/PDP.h"
+#include "hal/Ports.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    initializePDP
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PDPJNI_initializePDP
+  (JNIEnv* env, jclass, jint module)
+{
+  int32_t status = 0;
+  auto handle = HAL_InitializePDP(module, &status);
+  CheckStatusRange(env, status, 0, HAL_GetNumPDPModules(), module);
+  return static_cast<jint>(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    checkPDPChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PDPJNI_checkPDPChannel
+  (JNIEnv* env, jclass, jint channel)
+{
+  return HAL_CheckPDPChannel(channel);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    checkPDPModule
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PDPJNI_checkPDPModule
+  (JNIEnv* env, jclass, jint module)
+{
+  return HAL_CheckPDPModule(module);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    getPDPTemperature
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PDPJNI_getPDPTemperature
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  double temperature = HAL_GetPDPTemperature(handle, &status);
+  CheckStatus(env, status, false);
+  return temperature;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    getPDPVoltage
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PDPJNI_getPDPVoltage
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  double voltage = HAL_GetPDPVoltage(handle, &status);
+  CheckStatus(env, status, false);
+  return voltage;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    getPDPChannelCurrent
+ * Signature: (BI)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PDPJNI_getPDPChannelCurrent
+  (JNIEnv* env, jclass, jbyte channel, jint handle)
+{
+  int32_t status = 0;
+  double current = HAL_GetPDPChannelCurrent(handle, channel, &status);
+  CheckStatus(env, status, false);
+  return current;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    getPDPAllCurrents
+ * Signature: (I[D)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PDPJNI_getPDPAllCurrents
+  (JNIEnv* env, jclass, jint handle, jdoubleArray jarr)
+{
+  double storage[16];
+  int32_t status = 0;
+  HAL_GetPDPAllChannelCurrents(handle, storage, &status);
+  if (!CheckStatus(env, status, false)) {
+    return;
+  }
+
+  env->SetDoubleArrayRegion(jarr, 0, 16, storage);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    getPDPTotalCurrent
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PDPJNI_getPDPTotalCurrent
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  double current = HAL_GetPDPTotalCurrent(handle, &status);
+  CheckStatus(env, status, false);
+  return current;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    getPDPTotalPower
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PDPJNI_getPDPTotalPower
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  double power = HAL_GetPDPTotalPower(handle, &status);
+  CheckStatus(env, status, false);
+  return power;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    getPDPTotalEnergy
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PDPJNI_getPDPTotalEnergy
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  double energy = HAL_GetPDPTotalEnergy(handle, &status);
+  CheckStatus(env, status, false);
+  return energy;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    resetPDPTotalEnergy
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PDPJNI_resetPDPTotalEnergy
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  HAL_ResetPDPTotalEnergy(handle, &status);
+  CheckStatus(env, status, false);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    clearPDPStickyFaults
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PDPJNI_clearPDPStickyFaults
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  HAL_ClearPDPStickyFaults(handle, &status);
+  CheckStatus(env, status, false);
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/PWMJNI.cpp b/hal/src/main/native/cpp/jni/PWMJNI.cpp
new file mode 100644
index 0000000..80293c4
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/PWMJNI.cpp
@@ -0,0 +1,277 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_PWMJNI.h"
+#include "hal/DIO.h"
+#include "hal/PWM.h"
+#include "hal/Ports.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    initializePWMPort
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PWMJNI_initializePWMPort
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  auto pwm = HAL_InitializePWMPort((HAL_PortHandle)id, &status);
+  CheckStatusRange(env, status, 0, HAL_GetNumPWMChannels(),
+                   hal::getPortHandleChannel((HAL_PortHandle)id));
+  return (jint)pwm;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    checkPWMChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PWMJNI_checkPWMChannel
+  (JNIEnv* env, jclass, jint channel)
+{
+  return HAL_CheckPWMChannel(channel);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    freePWMPort
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_freePWMPort
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_FreePWMPort((HAL_DigitalHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMConfigRaw
+ * Signature: (IIIIII)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMConfigRaw
+  (JNIEnv* env, jclass, jint id, jint maxPwm, jint deadbandMaxPwm,
+   jint centerPwm, jint deadbandMinPwm, jint minPwm)
+{
+  int32_t status = 0;
+  HAL_SetPWMConfigRaw((HAL_DigitalHandle)id, maxPwm, deadbandMaxPwm, centerPwm,
+                      deadbandMinPwm, minPwm, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMConfig
+ * Signature: (IDDDDD)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMConfig
+  (JNIEnv* env, jclass, jint id, jdouble maxPwm, jdouble deadbandMaxPwm,
+   jdouble centerPwm, jdouble deadbandMinPwm, jdouble minPwm)
+{
+  int32_t status = 0;
+  HAL_SetPWMConfig((HAL_DigitalHandle)id, maxPwm, deadbandMaxPwm, centerPwm,
+                   deadbandMinPwm, minPwm, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    getPWMConfigRaw
+ * Signature: (I)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_first_hal_PWMJNI_getPWMConfigRaw
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  int32_t maxPwm = 0;
+  int32_t deadbandMaxPwm = 0;
+  int32_t centerPwm = 0;
+  int32_t deadbandMinPwm = 0;
+  int32_t minPwm = 0;
+  HAL_GetPWMConfigRaw((HAL_DigitalHandle)id, &maxPwm, &deadbandMaxPwm,
+                      &centerPwm, &deadbandMinPwm, &minPwm, &status);
+  CheckStatus(env, status);
+  return CreatePWMConfigDataResult(env, maxPwm, deadbandMaxPwm, centerPwm,
+                                   deadbandMinPwm, minPwm);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMEliminateDeadband
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMEliminateDeadband
+  (JNIEnv* env, jclass, jint id, jboolean value)
+{
+  int32_t status = 0;
+  HAL_SetPWMEliminateDeadband((HAL_DigitalHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    getPWMEliminateDeadband
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PWMJNI_getPWMEliminateDeadband
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  auto val = HAL_GetPWMEliminateDeadband((HAL_DigitalHandle)id, &status);
+  CheckStatus(env, status);
+  return (jboolean)val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMRaw
+ * Signature: (IS)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMRaw
+  (JNIEnv* env, jclass, jint id, jshort value)
+{
+  int32_t status = 0;
+  HAL_SetPWMRaw((HAL_DigitalHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMSpeed
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMSpeed
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  int32_t status = 0;
+  HAL_SetPWMSpeed((HAL_DigitalHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMPosition
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMPosition
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  int32_t status = 0;
+  HAL_SetPWMPosition((HAL_DigitalHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    getPWMRaw
+ * Signature: (I)S
+ */
+JNIEXPORT jshort JNICALL
+Java_edu_wpi_first_hal_PWMJNI_getPWMRaw
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jshort returnValue = HAL_GetPWMRaw((HAL_DigitalHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    getPWMSpeed
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PWMJNI_getPWMSpeed
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jdouble returnValue = HAL_GetPWMSpeed((HAL_DigitalHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    getPWMPosition
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PWMJNI_getPWMPosition
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jdouble returnValue = HAL_GetPWMPosition((HAL_DigitalHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMDisabled
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMDisabled
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_SetPWMDisabled((HAL_DigitalHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    latchPWMZero
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_latchPWMZero
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_LatchPWMZero((HAL_DigitalHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMPeriodScale
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMPeriodScale
+  (JNIEnv* env, jclass, jint id, jint value)
+{
+  int32_t status = 0;
+  HAL_SetPWMPeriodScale((HAL_DigitalHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/PortsJNI.cpp b/hal/src/main/native/cpp/jni/PortsJNI.cpp
new file mode 100644
index 0000000..1adb7fb
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/PortsJNI.cpp
@@ -0,0 +1,252 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_PortsJNI.h"
+#include "hal/Ports.h"
+
+using namespace frc;
+
+extern "C" {
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumAccumulators
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumAccumulators
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumAccumulators();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumAnalogTriggers
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumAnalogTriggers
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumAnalogTriggers();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumAnalogInputs
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumAnalogInputs
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumAnalogInputs();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumAnalogOutputs
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumAnalogOutputs
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumAnalogOutputs();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumCounters
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumCounters
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumCounters();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumDigitalHeaders
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumDigitalHeaders
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumDigitalHeaders();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumPWMHeaders
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumPWMHeaders
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumPWMHeaders();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumDigitalChannels
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumDigitalChannels
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumDigitalChannels();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumPWMChannels
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumPWMChannels
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumPWMChannels();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumDigitalPWMOutputs
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumDigitalPWMOutputs
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumDigitalPWMOutputs();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumEncoders
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumEncoders
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumEncoders();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumInterrupts
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumInterrupts
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumInterrupts();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumRelayChannels
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumRelayChannels
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumRelayChannels();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumRelayHeaders
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumRelayHeaders
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumRelayHeaders();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumPCMModules
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumPCMModules
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumPCMModules();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumSolenoidChannels
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumSolenoidChannels
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumSolenoidChannels();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumPDPModules
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumPDPModules
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumPDPModules();
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumPDPChannels
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumPDPChannels
+  (JNIEnv* env, jclass)
+{
+  jint value = HAL_GetNumPDPChannels();
+  return value;
+}
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/PowerJNI.cpp b/hal/src/main/native/cpp/jni/PowerJNI.cpp
new file mode 100644
index 0000000..9184e9e
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/PowerJNI.cpp
@@ -0,0 +1,228 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_PowerJNI.h"
+#include "hal/Power.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getVinVoltage
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getVinVoltage
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetVinVoltage(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getVinCurrent
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getVinCurrent
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetVinCurrent(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserVoltage6V
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserVoltage6V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetUserVoltage6V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserCurrent6V
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserCurrent6V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetUserCurrent6V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserActive6V
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserActive6V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  bool val = HAL_GetUserActive6V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserCurrentFaults6V
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserCurrentFaults6V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  int32_t val = HAL_GetUserCurrentFaults6V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserVoltage5V
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserVoltage5V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetUserVoltage5V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserCurrent5V
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserCurrent5V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetUserCurrent5V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserActive5V
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserActive5V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  bool val = HAL_GetUserActive5V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserCurrentFaults5V
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserCurrentFaults5V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  int32_t val = HAL_GetUserCurrentFaults5V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserVoltage3V3
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserVoltage3V3
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetUserVoltage3V3(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserCurrent3V3
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserCurrent3V3
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetUserCurrent3V3(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserActive3V3
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserActive3V3
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  bool val = HAL_GetUserActive3V3(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserCurrentFaults3V3
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserCurrentFaults3V3
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  int32_t val = HAL_GetUserCurrentFaults3V3(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/RelayJNI.cpp b/hal/src/main/native/cpp/jni/RelayJNI.cpp
new file mode 100644
index 0000000..c058435
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/RelayJNI.cpp
@@ -0,0 +1,92 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_RelayJNI.h"
+#include "hal/Ports.h"
+#include "hal/Relay.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_RelayJNI
+ * Method:    initializeRelayPort
+ * Signature: (IZ)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_RelayJNI_initializeRelayPort
+  (JNIEnv* env, jclass, jint id, jboolean fwd)
+{
+  int32_t status = 0;
+  HAL_RelayHandle handle = HAL_InitializeRelayPort(
+      (HAL_PortHandle)id, static_cast<uint8_t>(fwd), &status);
+  CheckStatusRange(env, status, 0, HAL_GetNumRelayChannels(),
+                   hal::getPortHandleChannel((HAL_PortHandle)id));
+  return (jint)handle;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_RelayJNI
+ * Method:    freeRelayPort
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_RelayJNI_freeRelayPort
+  (JNIEnv* env, jclass, jint id)
+{
+  HAL_FreeRelayPort((HAL_RelayHandle)id);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_RelayJNI
+ * Method:    checkRelayChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_RelayJNI_checkRelayChannel
+  (JNIEnv* env, jclass, jint channel)
+{
+  return (jboolean)HAL_CheckRelayChannel(static_cast<uint8_t>(channel));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_RelayJNI
+ * Method:    setRelay
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_RelayJNI_setRelay
+  (JNIEnv* env, jclass, jint id, jboolean value)
+{
+  int32_t status = 0;
+  HAL_SetRelay((HAL_RelayHandle)id, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_RelayJNI
+ * Method:    getRelay
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_RelayJNI_getRelay
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  jboolean returnValue = HAL_GetRelay((HAL_RelayHandle)id, &status);
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/SPIJNI.cpp b/hal/src/main/native/cpp/jni/SPIJNI.cpp
new file mode 100644
index 0000000..7962e21
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/SPIJNI.cpp
@@ -0,0 +1,413 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include <wpi/jni_util.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_SPIJNI.h"
+#include "hal/SPI.h"
+
+using namespace frc;
+using namespace wpi::java;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiInitialize
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiInitialize
+  (JNIEnv* env, jclass, jint port)
+{
+  int32_t status = 0;
+  HAL_InitializeSPI(static_cast<HAL_SPIPort>(port), &status);
+  CheckStatusForceThrow(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiTransaction
+ * Signature: (ILjava/lang/Object;Ljava/lang/Object;B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiTransaction
+  (JNIEnv* env, jclass, jint port, jobject dataToSend, jobject dataReceived,
+   jbyte size)
+{
+  uint8_t* dataToSendPtr = nullptr;
+  if (dataToSend != 0) {
+    dataToSendPtr =
+        reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataToSend));
+  }
+  uint8_t* dataReceivedPtr =
+      reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataReceived));
+  jint retVal = HAL_TransactionSPI(static_cast<HAL_SPIPort>(port),
+                                   dataToSendPtr, dataReceivedPtr, size);
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiTransactionB
+ * Signature: (I[B[BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiTransactionB
+  (JNIEnv* env, jclass, jint port, jbyteArray dataToSend,
+   jbyteArray dataReceived, jbyte size)
+{
+  wpi::SmallVector<uint8_t, 128> recvBuf;
+  recvBuf.resize(size);
+  jint retVal =
+      HAL_TransactionSPI(static_cast<HAL_SPIPort>(port),
+                         reinterpret_cast<const uint8_t*>(
+                             JByteArrayRef(env, dataToSend).array().data()),
+                         recvBuf.data(), size);
+  env->SetByteArrayRegion(dataReceived, 0, size,
+                          reinterpret_cast<const jbyte*>(recvBuf.data()));
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiWrite
+ * Signature: (ILjava/lang/Object;B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiWrite
+  (JNIEnv* env, jclass, jint port, jobject dataToSend, jbyte size)
+{
+  uint8_t* dataToSendPtr = nullptr;
+  if (dataToSend != 0) {
+    dataToSendPtr =
+        reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataToSend));
+  }
+  jint retVal =
+      HAL_WriteSPI(static_cast<HAL_SPIPort>(port), dataToSendPtr, size);
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiWriteB
+ * Signature: (I[BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiWriteB
+  (JNIEnv* env, jclass, jint port, jbyteArray dataToSend, jbyte size)
+{
+  jint retVal = HAL_WriteSPI(static_cast<HAL_SPIPort>(port),
+                             reinterpret_cast<const uint8_t*>(
+                                 JByteArrayRef(env, dataToSend).array().data()),
+                             size);
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiRead
+ * Signature: (IZLjava/lang/Object;B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiRead
+  (JNIEnv* env, jclass, jint port, jboolean initiate, jobject dataReceived,
+   jbyte size)
+{
+  uint8_t* dataReceivedPtr =
+      reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataReceived));
+  jint retVal;
+  if (initiate) {
+    wpi::SmallVector<uint8_t, 128> sendBuf;
+    sendBuf.resize(size);
+    retVal = HAL_TransactionSPI(static_cast<HAL_SPIPort>(port), sendBuf.data(),
+                                dataReceivedPtr, size);
+  } else {
+    retVal = HAL_ReadSPI(static_cast<HAL_SPIPort>(port),
+                         reinterpret_cast<uint8_t*>(dataReceivedPtr), size);
+  }
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiReadB
+ * Signature: (IZ[BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiReadB
+  (JNIEnv* env, jclass, jint port, jboolean initiate, jbyteArray dataReceived,
+   jbyte size)
+{
+  jint retVal;
+  wpi::SmallVector<uint8_t, 128> recvBuf;
+  recvBuf.resize(size);
+  if (initiate) {
+    wpi::SmallVector<uint8_t, 128> sendBuf;
+    sendBuf.resize(size);
+    retVal = HAL_TransactionSPI(static_cast<HAL_SPIPort>(port), sendBuf.data(),
+                                recvBuf.data(), size);
+  } else {
+    retVal = HAL_ReadSPI(static_cast<HAL_SPIPort>(port), recvBuf.data(), size);
+  }
+  env->SetByteArrayRegion(dataReceived, 0, size,
+                          reinterpret_cast<const jbyte*>(recvBuf.data()));
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiClose
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiClose
+  (JNIEnv*, jclass, jint port)
+{
+  HAL_CloseSPI(static_cast<HAL_SPIPort>(port));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiSetSpeed
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiSetSpeed
+  (JNIEnv*, jclass, jint port, jint speed)
+{
+  HAL_SetSPISpeed(static_cast<HAL_SPIPort>(port), speed);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiSetOpts
+ * Signature: (IIII)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiSetOpts
+  (JNIEnv*, jclass, jint port, jint msb_first, jint sample_on_trailing,
+   jint clk_idle_high)
+{
+  HAL_SetSPIOpts(static_cast<HAL_SPIPort>(port), msb_first, sample_on_trailing,
+                 clk_idle_high);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiSetChipSelectActiveHigh
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiSetChipSelectActiveHigh
+  (JNIEnv* env, jclass, jint port)
+{
+  int32_t status = 0;
+  HAL_SetSPIChipSelectActiveHigh(static_cast<HAL_SPIPort>(port), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiSetChipSelectActiveLow
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiSetChipSelectActiveLow
+  (JNIEnv* env, jclass, jint port)
+{
+  int32_t status = 0;
+  HAL_SetSPIChipSelectActiveLow(static_cast<HAL_SPIPort>(port), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiInitAuto
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiInitAuto
+  (JNIEnv* env, jclass, jint port, jint bufferSize)
+{
+  int32_t status = 0;
+  HAL_InitSPIAuto(static_cast<HAL_SPIPort>(port), bufferSize, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiFreeAuto
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiFreeAuto
+  (JNIEnv* env, jclass, jint port)
+{
+  int32_t status = 0;
+  HAL_FreeSPIAuto(static_cast<HAL_SPIPort>(port), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiStartAutoRate
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiStartAutoRate
+  (JNIEnv* env, jclass, jint port, jdouble period)
+{
+  int32_t status = 0;
+  HAL_StartSPIAutoRate(static_cast<HAL_SPIPort>(port), period, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiStartAutoTrigger
+ * Signature: (IIIZZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiStartAutoTrigger
+  (JNIEnv* env, jclass, jint port, jint digitalSourceHandle,
+   jint analogTriggerType, jboolean triggerRising, jboolean triggerFalling)
+{
+  int32_t status = 0;
+  HAL_StartSPIAutoTrigger(static_cast<HAL_SPIPort>(port), digitalSourceHandle,
+                          static_cast<HAL_AnalogTriggerType>(analogTriggerType),
+                          triggerRising, triggerFalling, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiStopAuto
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiStopAuto
+  (JNIEnv* env, jclass, jint port)
+{
+  int32_t status = 0;
+  HAL_StopSPIAuto(static_cast<HAL_SPIPort>(port), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiSetAutoTransmitData
+ * Signature: (I[BI)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiSetAutoTransmitData
+  (JNIEnv* env, jclass, jint port, jbyteArray dataToSend, jint zeroSize)
+{
+  JByteArrayRef jarr(env, dataToSend);
+  int32_t status = 0;
+  HAL_SetSPIAutoTransmitData(
+      static_cast<HAL_SPIPort>(port),
+      reinterpret_cast<const uint8_t*>(jarr.array().data()),
+      jarr.array().size(), zeroSize, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiForceAutoRead
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiForceAutoRead
+  (JNIEnv* env, jclass, jint port)
+{
+  int32_t status = 0;
+  HAL_ForceSPIAutoRead(static_cast<HAL_SPIPort>(port), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiReadAutoReceivedData
+ * Signature: (ILjava/lang/Object;ID)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiReadAutoReceivedData__ILjava_nio_ByteBuffer_2ID
+  (JNIEnv* env, jclass, jint port, jobject buffer, jint numToRead,
+   jdouble timeout)
+{
+  uint32_t* recvBuf =
+      reinterpret_cast<uint32_t*>(env->GetDirectBufferAddress(buffer));
+  int32_t status = 0;
+  jint retval = HAL_ReadSPIAutoReceivedData(
+      static_cast<HAL_SPIPort>(port), recvBuf, numToRead, timeout, &status);
+  CheckStatus(env, status);
+  return retval;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiReadAutoReceivedData
+ * Signature: (I[IID)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiReadAutoReceivedData__I_3IID
+  (JNIEnv* env, jclass, jint port, jintArray buffer, jint numToRead,
+   jdouble timeout)
+{
+  wpi::SmallVector<uint32_t, 128> recvBuf;
+  recvBuf.resize(numToRead);
+  int32_t status = 0;
+  jint retval =
+      HAL_ReadSPIAutoReceivedData(static_cast<HAL_SPIPort>(port),
+                                  recvBuf.data(), numToRead, timeout, &status);
+  if (!CheckStatus(env, status)) return retval;
+  if (numToRead > 0) {
+    env->SetIntArrayRegion(buffer, 0, numToRead,
+                           reinterpret_cast<const jint*>(recvBuf.data()));
+  }
+  return retval;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiGetAutoDroppedCount
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiGetAutoDroppedCount
+  (JNIEnv* env, jclass, jint port)
+{
+  int32_t status = 0;
+  auto retval =
+      HAL_GetSPIAutoDroppedCount(static_cast<HAL_SPIPort>(port), &status);
+  CheckStatus(env, status);
+  return retval;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiConfigureAutoStall
+ * Signature: (IIII)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiConfigureAutoStall
+  (JNIEnv* env, jclass, jint port, jint csToSclkTicks, jint stallTicks,
+   jint pow2BytesPerRead)
+{
+  int32_t status = 0;
+  HAL_ConfigureSPIAutoStall(static_cast<HAL_SPIPort>(port), csToSclkTicks,
+                            stallTicks, pow2BytesPerRead, &status);
+  CheckStatus(env, status);
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/SerialPortJNI.cpp b/hal/src/main/native/cpp/jni/SerialPortJNI.cpp
new file mode 100644
index 0000000..9fe9d92
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/SerialPortJNI.cpp
@@ -0,0 +1,318 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include <wpi/jni_util.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_SerialPortJNI.h"
+#include "hal/SerialPort.h"
+
+using namespace frc;
+using namespace wpi::java;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialInitializePort
+ * Signature: (B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialInitializePort
+  (JNIEnv* env, jclass, jbyte port)
+{
+  int32_t status = 0;
+  auto handle =
+      HAL_InitializeSerialPort(static_cast<HAL_SerialPort>(port), &status);
+  CheckStatusForceThrow(env, status);
+  return static_cast<jint>(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialInitializePortDirect
+ * Signature: (BLjava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialInitializePortDirect
+  (JNIEnv* env, jclass, jbyte port, jstring portName)
+{
+  JStringRef portNameRef{env, portName};
+  int32_t status = 0;
+  auto handle = HAL_InitializeSerialPortDirect(
+      static_cast<HAL_SerialPort>(port), portNameRef.c_str(), &status);
+  CheckStatusForceThrow(env, status);
+  return static_cast<jint>(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetBaudRate
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetBaudRate
+  (JNIEnv* env, jclass, jint handle, jint rate)
+{
+  int32_t status = 0;
+  HAL_SetSerialBaudRate(static_cast<HAL_SerialPortHandle>(handle), rate,
+                        &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetDataBits
+ * Signature: (IB)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetDataBits
+  (JNIEnv* env, jclass, jint handle, jbyte bits)
+{
+  int32_t status = 0;
+  HAL_SetSerialDataBits(static_cast<HAL_SerialPortHandle>(handle), bits,
+                        &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetParity
+ * Signature: (IB)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetParity
+  (JNIEnv* env, jclass, jint handle, jbyte parity)
+{
+  int32_t status = 0;
+  HAL_SetSerialParity(static_cast<HAL_SerialPortHandle>(handle), parity,
+                      &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetStopBits
+ * Signature: (IB)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetStopBits
+  (JNIEnv* env, jclass, jint handle, jbyte bits)
+{
+  int32_t status = 0;
+  HAL_SetSerialStopBits(static_cast<HAL_SerialPortHandle>(handle), bits,
+                        &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetWriteMode
+ * Signature: (IB)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetWriteMode
+  (JNIEnv* env, jclass, jint handle, jbyte mode)
+{
+  int32_t status = 0;
+  HAL_SetSerialWriteMode(static_cast<HAL_SerialPortHandle>(handle), mode,
+                         &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetFlowControl
+ * Signature: (IB)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetFlowControl
+  (JNIEnv* env, jclass, jint handle, jbyte flow)
+{
+  int32_t status = 0;
+  HAL_SetSerialFlowControl(static_cast<HAL_SerialPortHandle>(handle), flow,
+                           &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetTimeout
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetTimeout
+  (JNIEnv* env, jclass, jint handle, jdouble timeout)
+{
+  int32_t status = 0;
+  HAL_SetSerialTimeout(static_cast<HAL_SerialPortHandle>(handle), timeout,
+                       &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialEnableTermination
+ * Signature: (IC)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialEnableTermination
+  (JNIEnv* env, jclass, jint handle, jchar terminator)
+{
+  int32_t status = 0;
+  HAL_EnableSerialTermination(static_cast<HAL_SerialPortHandle>(handle),
+                              terminator, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialDisableTermination
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialDisableTermination
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  HAL_DisableSerialTermination(static_cast<HAL_SerialPortHandle>(handle),
+                               &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetReadBufferSize
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetReadBufferSize
+  (JNIEnv* env, jclass, jint handle, jint size)
+{
+  int32_t status = 0;
+  HAL_SetSerialReadBufferSize(static_cast<HAL_SerialPortHandle>(handle), size,
+                              &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetWriteBufferSize
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetWriteBufferSize
+  (JNIEnv* env, jclass, jint handle, jint size)
+{
+  int32_t status = 0;
+  HAL_SetSerialWriteBufferSize(static_cast<HAL_SerialPortHandle>(handle), size,
+                               &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialGetBytesReceived
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialGetBytesReceived
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  jint retVal = HAL_GetSerialBytesReceived(
+      static_cast<HAL_SerialPortHandle>(handle), &status);
+  CheckStatus(env, status);
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialRead
+ * Signature: (I[BI)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialRead
+  (JNIEnv* env, jclass, jint handle, jbyteArray dataReceived, jint size)
+{
+  wpi::SmallVector<char, 128> recvBuf;
+  recvBuf.resize(size);
+  int32_t status = 0;
+  jint retVal = HAL_ReadSerial(static_cast<HAL_SerialPortHandle>(handle),
+                               recvBuf.data(), size, &status);
+  env->SetByteArrayRegion(dataReceived, 0, size,
+                          reinterpret_cast<const jbyte*>(recvBuf.data()));
+  CheckStatus(env, status);
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialWrite
+ * Signature: (I[BI)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialWrite
+  (JNIEnv* env, jclass, jint handle, jbyteArray dataToSend, jint size)
+{
+  int32_t status = 0;
+  jint retVal =
+      HAL_WriteSerial(static_cast<HAL_SerialPortHandle>(handle),
+                      reinterpret_cast<const char*>(
+                          JByteArrayRef(env, dataToSend).array().data()),
+                      size, &status);
+  CheckStatus(env, status);
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialFlush
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialFlush
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  HAL_FlushSerial(static_cast<HAL_SerialPortHandle>(handle), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialClear
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialClear
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  HAL_ClearSerial(static_cast<HAL_SerialPortHandle>(handle), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialClose
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialClose
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  HAL_CloseSerial(static_cast<HAL_SerialPortHandle>(handle), &status);
+  CheckStatus(env, status);
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/SimDeviceJNI.cpp b/hal/src/main/native/cpp/jni/SimDeviceJNI.cpp
new file mode 100644
index 0000000..d9652cc
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/SimDeviceJNI.cpp
@@ -0,0 +1,168 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <wpi/jni_util.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_SimDeviceJNI.h"
+#include "hal/SimDevice.h"
+
+using namespace wpi::java;
+
+static HAL_Value ValueFromJava(jint type, jlong value1, jdouble value2) {
+  HAL_Value value;
+  value.type = static_cast<HAL_Type>(type);
+  switch (value.type) {
+    case HAL_BOOLEAN:
+      value.data.v_boolean = value1;
+      break;
+    case HAL_DOUBLE:
+      value.data.v_double = value2;
+      break;
+    case HAL_ENUM:
+      value.data.v_enum = value1;
+      break;
+    case HAL_INT:
+      value.data.v_int = value1;
+      break;
+    case HAL_LONG:
+      value.data.v_long = value1;
+      break;
+    default:
+      break;
+  }
+  return value;
+}
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_SimDeviceJNI
+ * Method:    createSimDevice
+ * Signature: (Ljava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SimDeviceJNI_createSimDevice
+  (JNIEnv* env, jclass, jstring name)
+{
+  return HAL_CreateSimDevice(JStringRef{env, name}.c_str());
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SimDeviceJNI
+ * Method:    freeSimDevice
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SimDeviceJNI_freeSimDevice
+  (JNIEnv*, jclass, jint handle)
+{
+  HAL_FreeSimDevice(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SimDeviceJNI
+ * Method:    createSimValueNative
+ * Signature: (ILjava/lang/String;ZIJD)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SimDeviceJNI_createSimValueNative
+  (JNIEnv* env, jclass, jint device, jstring name, jboolean readonly, jint type,
+   jlong value1, jdouble value2)
+{
+  return HAL_CreateSimValue(device, JStringRef{env, name}.c_str(), readonly,
+                            ValueFromJava(type, value1, value2));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SimDeviceJNI
+ * Method:    createSimValueEnum
+ * Signature: (ILjava/lang/String;Z[Ljava/lang/Object;I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SimDeviceJNI_createSimValueEnum
+  (JNIEnv* env, jclass, jint device, jstring name, jboolean readonly,
+   jobjectArray options, jint initialValue)
+{
+  size_t len = env->GetArrayLength(options);
+  std::vector<std::string> arr;
+  arr.reserve(len);
+  for (size_t i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(options, i))};
+    if (!elem) return 0;
+    arr.push_back(JStringRef{env, elem}.str());
+  }
+  wpi::SmallVector<const char*, 8> carr;
+  for (auto&& val : arr) carr.push_back(val.c_str());
+  return HAL_CreateSimValueEnum(device, JStringRef{env, name}.c_str(), readonly,
+                                len, carr.data(), initialValue);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SimDeviceJNI
+ * Method:    getSimValue
+ * Signature: (I)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_first_hal_SimDeviceJNI_getSimValue
+  (JNIEnv* env, jclass, jint handle)
+{
+  return frc::CreateHALValue(env, HAL_GetSimValue(handle));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SimDeviceJNI
+ * Method:    getSimValueDouble
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_SimDeviceJNI_getSimValueDouble
+  (JNIEnv*, jclass, jint handle)
+{
+  return HAL_GetSimValueDouble(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SimDeviceJNI
+ * Method:    getSimValueEnum
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SimDeviceJNI_getSimValueEnum
+  (JNIEnv*, jclass, jint handle)
+{
+  return HAL_GetSimValueEnum(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SimDeviceJNI
+ * Method:    getSimValueBoolean
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_SimDeviceJNI_getSimValueBoolean
+  (JNIEnv*, jclass, jint handle)
+{
+  return HAL_GetSimValueBoolean(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SimDeviceJNI
+ * Method:    setSimValueNative
+ * Signature: (IIJD)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SimDeviceJNI_setSimValueNative
+  (JNIEnv*, jclass, jint handle, jint type, jlong value1, jdouble value2)
+{
+  HAL_SetSimValue(handle, ValueFromJava(type, value1, value2));
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/SolenoidJNI.cpp b/hal/src/main/native/cpp/jni/SolenoidJNI.cpp
new file mode 100644
index 0000000..4e6f139
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/SolenoidJNI.cpp
@@ -0,0 +1,203 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_SolenoidJNI.h"
+#include "hal/Ports.h"
+#include "hal/Solenoid.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    initializeSolenoidPort
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_initializeSolenoidPort
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  HAL_SolenoidHandle handle =
+      HAL_InitializeSolenoidPort((HAL_PortHandle)id, &status);
+
+  // Use solenoid channels, as we have to pick one.
+  CheckStatusRange(env, status, 0, HAL_GetNumSolenoidChannels(),
+                   hal::getPortHandleChannel((HAL_PortHandle)id));
+  return (jint)handle;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    checkSolenoidChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_checkSolenoidChannel
+  (JNIEnv* env, jclass, jint channel)
+{
+  return HAL_CheckSolenoidChannel(channel);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    checkSolenoidModule
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_checkSolenoidModule
+  (JNIEnv* env, jclass, jint module)
+{
+  return HAL_CheckSolenoidModule(module);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    freeSolenoidPort
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_freeSolenoidPort
+  (JNIEnv* env, jclass, jint id)
+{
+  HAL_FreeSolenoidPort((HAL_SolenoidHandle)id);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    setSolenoid
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_setSolenoid
+  (JNIEnv* env, jclass, jint solenoid_port, jboolean value)
+{
+  int32_t status = 0;
+  HAL_SetSolenoid((HAL_SolenoidHandle)solenoid_port, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    getSolenoid
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_getSolenoid
+  (JNIEnv* env, jclass, jint solenoid_port)
+{
+  int32_t status = 0;
+  jboolean val = HAL_GetSolenoid((HAL_SolenoidHandle)solenoid_port, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    getAllSolenoids
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_getAllSolenoids
+  (JNIEnv* env, jclass, jint module)
+{
+  int32_t status = 0;
+  jint val = HAL_GetAllSolenoids(module, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    getPCMSolenoidBlackList
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_getPCMSolenoidBlackList
+  (JNIEnv* env, jclass, jint module)
+{
+  int32_t status = 0;
+  jint val = HAL_GetPCMSolenoidBlackList(module, &status);
+  CheckStatus(env, status);
+  return val;
+}
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    getPCMSolenoidVoltageStickyFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_getPCMSolenoidVoltageStickyFault
+  (JNIEnv* env, jclass, jint module)
+{
+  int32_t status = 0;
+  bool val = HAL_GetPCMSolenoidVoltageStickyFault(module, &status);
+  CheckStatus(env, status);
+  return val;
+}
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    getPCMSolenoidVoltageFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_getPCMSolenoidVoltageFault
+  (JNIEnv* env, jclass, jint module)
+{
+  int32_t status = 0;
+  bool val = HAL_GetPCMSolenoidVoltageFault(module, &status);
+  CheckStatus(env, status);
+  return val;
+}
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    clearAllPCMStickyFaults
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_clearAllPCMStickyFaults
+  (JNIEnv* env, jclass, jint module)
+{
+  int32_t status = 0;
+  HAL_ClearAllPCMStickyFaults(module, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    setOneShotDuration
+ * Signature: (IJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_setOneShotDuration
+  (JNIEnv* env, jclass, jint solenoid_port, jlong durationMS)
+{
+  int32_t status = 0;
+  HAL_SetOneShotDuration((HAL_SolenoidHandle)solenoid_port, durationMS,
+                         &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    fireOneShot
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_fireOneShot
+  (JNIEnv* env, jclass, jint solenoid_port)
+{
+  int32_t status = 0;
+  HAL_FireOneShot((HAL_SolenoidHandle)solenoid_port, &status);
+  CheckStatus(env, status);
+}
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/ThreadsJNI.cpp b/hal/src/main/native/cpp/jni/ThreadsJNI.cpp
new file mode 100644
index 0000000..d4620e2
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/ThreadsJNI.cpp
@@ -0,0 +1,67 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_ThreadsJNI.h"
+#include "hal/Threads.h"
+
+using namespace frc;
+
+extern "C" {
+/*
+ * Class:     edu_wpi_first_hal_ThreadsJNI
+ * Method:    getCurrentThreadPriority
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_ThreadsJNI_getCurrentThreadPriority
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  HAL_Bool isRT = false;
+  auto ret = HAL_GetCurrentThreadPriority(&isRT, &status);
+  CheckStatus(env, status);
+  return (jint)ret;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_ThreadsJNI
+ * Method:    getCurrentThreadIsRealTime
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_ThreadsJNI_getCurrentThreadIsRealTime
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  HAL_Bool isRT = false;
+  HAL_GetCurrentThreadPriority(&isRT, &status);
+  CheckStatus(env, status);
+  return (jboolean)isRT;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_ThreadsJNI
+ * Method:    setCurrentThreadPriority
+ * Signature: (ZI)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_ThreadsJNI_setCurrentThreadPriority
+  (JNIEnv* env, jclass, jboolean realTime, jint priority)
+{
+  int32_t status = 0;
+  auto ret = HAL_SetCurrentThreadPriority(
+      (HAL_Bool)realTime, static_cast<int32_t>(priority), &status);
+  CheckStatus(env, status);
+  return (jboolean)ret;
+}
+
+}  // extern "C"