Squashed 'third_party/allwpilib_2019/' changes from 936627bd9..a3f7420da

e20d96ea4 Use __has_include for WPILib.h (#2164)
a76d006a0 Update native-utils to 2020.7.2 (#2161)
24c031d69 Increase SPI auto byte count to allow 32 bytes to be sent (#2163)
6b4eecf5f Add hidden functions to get the SPI system and SPI DMA (#2162)
ccdd0fbdb Add TrapezoidProfile external PID examples (#2131)
5c6b8a0f4 Replace std::is_pod_v with std::is_standard_layout_v (#2159)
67d2fed68 Add DutyCycleEncoder channel constructor (#2158)
d8f11eb14 Hardcode channels for LSB weight (#2153)
b2ae75acd Add way to disable "no extensions found" message (#2134)
4f951789f Build testbench tests online inorder to improve speed (#2144)
005c4c5be Try catch around task dependencies to fix loading in editor (#2156)
34f6b3f4c Fix C++ RamseteCommand param doxygen (#2157)
f7a93713f Fix up templated TrapezoidProfile classes (#2151)
8c2ff94d7 Rename MathUtils to MathUtil for consistency with other util classes (#2155)
d003ec2dc Update to 2020v9 image (#2154)
8e7cc3fe7 Add user-friendly SimDeviceSim wrappers (#2150)
6c8f6cf47 Fix bug in cubic and quintic hermetic spline generation (#2139)
e37ecd33a Sim GUI: Add support for LED displays (#2138)
57c5523d6 Fix documentation in RamseteCommand (#2149)
7b9c6ebc2 Fix wpiutilJNIShared linkage typo in wpilibj (#2143)
9a515c80f Template C++ LinearFilter to work with unit types (#2142)
5b73c17f2 Remove encoder velocities methods in DifferentialDriveOdometry (#2147)
b8c102426 Fix PS3Eye VID and PID (#2146)
2622c6c29 Add default values for b and zeta in RamseteController (#2145)
f66ae5999 Add HSV helpers to AddressableLED (#2135)
5e97c81d8 Add MedianFilter class for moving-window median (#2136)
f79b7a058 Remove unnecessary constructor arg for LinearFilter's circular buffers (#2140)
e49494830 Replace Jenkins with Azure agent (#1914)
b67d049ac Check status of PDP CAN reads (#2126)
70102a60b SendableRegistry.foreachLiveWindow: Prevent concurrent modification (#2129)
6dcd2b0e2 Improve various subsystem APIs (#2130)
ce3973435 HAL_CAN_ReceiveMessage: return MessageNotFound if no callbacks registered (#2133)
3fcfc8ea7 Fix double disable segfaulting interrupts (#2132)
6ceafe3cd Fix class reference for logger (#2123)
b058dcf64 Catch exceptions generated by OpenCV in cscore JNI (#2118)
0b9307fdf Remove unused parts of .styleguide files (#2119)
39be812b2 Fix C++ ArmFeedforward (#2120)
21e957ee4 Add DifferentialDrive voltage constraint (#2075)
e0bc97f66 Add ProfiledPIDSubsystem example (#2076)
3df44c874 Remove Rotation2d.h wpi/math include (#2117)
a58dbec8a Add holonomic follower examples (#2052)
9a8067465 Fix incomplete .styleguide (#2113)
ffa4b907c Fix C++ floating point literal formatting (#2114)
3d1ca856b Fix missing typename and return type (#2115)
5f85457a9 Add usage reporting for AddressableLED (#2108)
4ebae1712 Enforce leading/trailing zeros in Java numeric constants (#2105)
fa85fbfc1 Template C++ TrapezoidProfile and ProfiledPIDController on units (#2109)
f62e23f1a Add Doxygen for new HAL interfaces (#2110)
5443fdabc Directly construct PWM port from HAL, avoid wpilib PWM object (#2106)
c0e36df9d Standardize on PWMVictorSPX in examples (#2104)
8c4d9f541 Add TrapezoidProfileSubsystem (#2077)
45201d15f Add encoder distance overload to DifferentialDriveOdometry (#2096)
845aba33f Make feedforward classes constexpr (#2103)
500c43fb8 Add examples for DMA, DutyCycle, DutyCycleEncoder and AddressableLED (#2100)
589162811 Use DifferentialDriveWheelSpeeds in RamseteCommand ctor (#2091)
b37b68daa Add JRE deployment to MyRobot Deploy (#2099)
0e83c65d2 Fix small logic error in ParallelDeadlineGroup (#2095)
6f6c6da9f Updates to addressable LED (#2098)
1894219ef Fix devmain package in commands (#2097)
77a9949bb Add AddressableLED simulation GUI support
a4c9e4ec2 Add AddressableLED simulation support
8ed205907 Add AddressableLED (#2092)
59507b12d Bump to 2020 v7 image (#2086)
5d39bf806 Make halsimgui::DrawLEDs() values parameter const (#2088)
841ef91c0 Use gyro angle instead of robot angle for odometry (#2081)
1b66ead49 Use standard constant for pi instead of 3.14 (#2084)
db2c3dddd Use DMA Global Number for DMA Index (#2085)
82b2170fe Add DMA support to HAL and WPILibC (#2080)
8280b7e3a Add DutyCycleEncoder and AnalogEncoder (#2040)
551096006 Use kNumSystems for DutyCycle count in Ports (#2083)
df1065218 Remove release configs of deploy in MyRobot (#2082)
bf5388393 Add deploy options to myRobot (#2079)
b7bc1ea74 Update to 2020v6 image (#2078)
708009cd2 Update to gradle 6.0 (#2074)
3cce61b89 Add SmartDashboard::GetEntry function in C++ (#2064)
565e1f3e7 Fix spelling in MecanumDriveOdometry docs (#2072)
1853f7b6b Add timing window to simulation GUI
c5a049712 Add simulation pause/resume/step support
f5446c740 Add Notifier HALSIM access
3e049e02f Add name to HAL Notifier
2da64d15f Make usage reporting enums type match (#2069)
f04d95e50 Make FRCUsageReporting.h C-compatible (#2070)
d748c67a5 Generate docs for command libraries and fix doclint enable (#2071)
55a7f2b4a Add template for old command-based style (#2031)
486fa9c69 Add XboxController examples for arcade and tank drive (#2058)
e3dd1c5d7 Fix small bug in SplineHelper (#2061)
7dc7c71b5 Add feedforward components (#2045)
5f33d6af1 Fix ProfiledPIDSubsystem parameter name (#2017)
94843adb8 Standardize documentation of Speed Controllers bounds (#2043)
9bcff37b9 Add HAL specific version of wpi_setError (#2055)
326aecc9a Add error message for CAN Write Overrun (#2062)
00228678d Add requirements param to more Command APIs (#2059)
ff39a96ce Make DigitalOutput a DigitalSource (#2054)
5ccad2e8a Fix frc2::Timer returning incorrect timestamp values (#2057)
629e95776 Add VendorDeps JSON files for command libraries (#2048)
6858a57f7 Make notifier command tests a lot more lenient (#2056)
0ebe32823 Fix MyRobotStatic accidentally linking to shared command libs (#2046)
384d00f9e Fix various duty cycle bugs (#2047)
1f6850adf Add CAN Manufacturer for Studica (#2050)
7508aada9 Add ability to end startCompetition() main loop (#2032)
f5b4be16d Old C++ Command: Make GetName et al public (#2042)
e6f5c93ab Clean up new C++ commands (#2027)
39f46ceab Don't allow rising and falling values to be read from AnalogTrigger (#2039)
d93aa2b6b Add missing lock in FRCDriverStation (#2034)
114ddaf81 Fix duplicate encoders in examples (#2033)
f22d0961e Sim GUI: Add duty cycle support
3262c2bad Sim GUI: Use new multi-channel PDP getter function
96d40192a Revert accidental change to MyRobot.cpp (#2029)
ed30d5d40 Add JSON support for Trajectories (#2025)
2b6811edd Fix null pointer dereference in C++ CommandScheduler (#2023)
1d695a166 Add FPGA Duty Cycle support (#1987)
509819d83 Split the two command implementations into separate libraries (#2012)
2ad15cae1 Add multi PDP getter and sim PCM/PDP multi arg functions (#2014)
931b8ceef Add new usage reporting types from 2020v5 (#2026)
0b3821eba Change files with CRLF line endings to LF (#2022)
6f159d142 Add way to atomically check for new data, and wait otherwise (#2015)
a769f1f22 Fix bug in RamseteCommand (using degrees instead of radians) (#2020)
c5186d815 Clean up PIDCommand (#2010)
9ebd23d61 Add setVoltage method to SpeedController (#1997)
f6e311ef8 Fix SplineHelper bug (#2018)
f33bd9f05 Fix NPE in RamseteCommand (#2019)
1c1e0c9a6 Add HAL_SetAllSolenoids to sim (#2004)
ea9bb651a Remove accidental OpenCV link from wpilibc shared library (#2013)
cc0742518 Change command decorators to return implementation (#2007)
16b34cce2 Remove IterativeRobot templates (#2011)
669127e49 Update intellisense to work with Beta 2020 code (#2008)
9dc30797e Fix usage reporting indices (#2009)
f6b844ea3 Move HAL Interrupt struct to anonymous namespace (#2003)
a72f80991 Add extern C to DigitalGlitchFilterJNI (#2002)
916596cb0 Fix invalid examples json, add validator (#2001)
5509a8e96 Use constexpr for all example constants
0be6b6475 Use constexpr for DifferentialDriveKinematics

Change-Id: I1416646cbab487ad8021830215766d8ec7f24ddc
git-subtree-dir: third_party/allwpilib_2019
git-subtree-split: a3f7420dab7a104c27a0c3bf0872c999c98fd9a9
diff --git a/hal/build.gradle b/hal/build.gradle
index 56b220d..d744259 100644
--- a/hal/build.gradle
+++ b/hal/build.gradle
@@ -185,3 +185,14 @@
         }
     }
 }
+
+model {
+    binaries {
+        all {
+            if (!(it instanceof NativeBinarySpec)) return
+            if (it.component.name != 'hal' && it.component.name != 'halBase') return
+            if (it.targetPlatform.name != nativeUtils.wpi.platforms.roborio) return
+            nativeUtils.useRequiredLibrary(it, 'netcomm_shared', 'chipobject_shared', 'visa_shared')
+        }
+    }
+}
diff --git a/hal/src/generate/FRCUsageReporting.h.in b/hal/src/generate/FRCUsageReporting.h.in
index 0ed3b33..34330c8 100644
--- a/hal/src/generate/FRCUsageReporting.h.in
+++ b/hal/src/generate/FRCUsageReporting.h.in
@@ -1,14 +1,54 @@
 #pragma once
 
+#include <stdint.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+// ifdef's definition is to allow for default parameters in C++.
+#ifdef __cplusplus
+/**
+ * Reports a hardware usage to the HAL.
+ *
+ * @param resource       the used resource
+ * @param instanceNumber the instance of the resource
+ * @param context        a user specified context index
+ * @param feature        a user specified feature string
+ * @return               the index of the added value in NetComm
+ */
+int64_t HAL_Report(int32_t resource, int32_t instanceNumber,
+                   int32_t context = 0, const char* feature = nullptr);
+#else
+
+/**
+ * Reports a hardware usage to the HAL.
+ *
+ * @param resource       the used resource
+ * @param instanceNumber the instance of the resource
+ * @param context        a user specified context index
+ * @param feature        a user specified feature string
+ * @return               the index of the added value in NetComm
+ */
+int64_t HAL_Report(int32_t resource, int32_t instanceNumber, int32_t context,
+                   const char* feature);
+#endif
+
+#ifdef __cplusplus
+}
+#endif
+
 /*
  * Autogenerated file! Do not manually edit this file.
  */
 
+#ifdef __cplusplus
 namespace HALUsageReporting {
-  typedef enum {
+  enum tResourceType : int32_t {
 ${usage_reporting_types_cpp}
-  } tResourceType;
-  typedef enum {
+  };
+  enum tInstances : int32_t {
 ${usage_reporting_instances_cpp}
-  } tInstances;
+  };
 }
+#endif
diff --git a/hal/src/generate/ResourceType.txt b/hal/src/generate/ResourceType.txt
index 1c9068a..4ee8eb2 100644
--- a/hal/src/generate/ResourceType.txt
+++ b/hal/src/generate/ResourceType.txt
@@ -62,7 +62,7 @@
 kResourceType_PigeonIMU = 61
 kResourceType_NidecBrushless = 62
 kResourceType_CANifier = 63
-kResourceType_CTRE_future0 = 64
+kResourceType_TalonFX = 64
 kResourceType_CTRE_future1 = 65
 kResourceType_CTRE_future2 = 66
 kResourceType_CTRE_future3 = 67
@@ -83,3 +83,12 @@
 kResourceType_RevSparkMaxPWM = 82
 kResourceType_RevSparkMaxCAN = 83
 kResourceType_ADIS16470 = 84
+kResourceType_PIDController2 = 85
+kResourceType_ProfiledPIDController = 86
+kResourceType_Kinematics = 87
+kResourceType_Odometry = 88
+kResourceType_Units = 89
+kResourceType_TrapezoidProfile = 90
+kResourceType_DutyCycle = 91
+kResourceType_AddressableLEDs = 92
+kResourceType_FusionVenom = 93
diff --git a/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java b/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java
new file mode 100644
index 0000000..fb34996
--- /dev/null
+++ b/hal/src/main/java/edu/wpi/first/hal/AddressableLEDJNI.java
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+@SuppressWarnings("AbbreviationAsWordInName")
+public class AddressableLEDJNI extends JNIWrapper {
+  public static native int initialize(int pwmHandle);
+  public static native void free(int handle);
+
+  public static native void setLength(int handle, int length);
+  public static native void setData(int handle, byte[] data);
+
+  public static native void setBitTiming(int handle, int lowTime0, int highTime0, int lowTime1, int highTime1);
+  public static native void setSyncTime(int handle, int syncTime);
+
+  public static native void start(int handle);
+  public static native void stop(int handle);
+}
diff --git a/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java b/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java
index 38e67a7..449c065 100644
--- a/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java
@@ -7,8 +7,6 @@
 
 package edu.wpi.first.hal;
 
-import java.nio.IntBuffer;
-
 public class AnalogJNI extends JNIWrapper {
   /**
    * <i>native declaration : AthenaJava\target\native\include\HAL\Analog.h:58</i><br> enum values
@@ -94,13 +92,18 @@
 
   public static native void getAccumulatorOutput(int analogPortHandle, AccumulatorResult result);
 
-  public static native int initializeAnalogTrigger(int analogInputHandle, IntBuffer index);
+  public static native int initializeAnalogTrigger(int analogInputHandle);
+
+  public static native int initializeAnalogTriggerDutyCycle(int dutyCycleHandle);
 
   public static native void cleanAnalogTrigger(int analogTriggerHandle);
 
   public static native void setAnalogTriggerLimitsRaw(int analogTriggerHandle, int lower,
                                                       int upper);
 
+  public static native void setAnalogTriggerLimitsDutyCycle(int analogTriggerHandle, double lower,
+                                                            double higher);
+
   public static native void setAnalogTriggerLimitsVoltage(int analogTriggerHandle,
                                                           double lower, double upper);
 
@@ -115,4 +118,7 @@
   public static native boolean getAnalogTriggerTriggerState(int analogTriggerHandle);
 
   public static native boolean getAnalogTriggerOutput(int analogTriggerHandle, int type);
+
+  @SuppressWarnings("AbbreviationAsWordInName")
+  public static native int getAnalogTriggerFPGAIndex(int analogTriggerHandle);
 }
diff --git a/hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java b/hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java
new file mode 100644
index 0000000..f0f93e1
--- /dev/null
+++ b/hal/src/main/java/edu/wpi/first/hal/DutyCycleJNI.java
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class DutyCycleJNI extends JNIWrapper {
+  public static native int initialize(int digitalSourceHandle, int analogTriggerType);
+  public static native void free(int handle);
+
+  public static native int getFrequency(int handle);
+  public static native double getOutput(int handle);
+  public static native int getOutputRaw(int handle);
+  public static native int getOutputScaleFactor(int handle);
+
+  @SuppressWarnings("AbbreviationAsWordInName")
+  public static native int getFPGAIndex(int handle);
+}
diff --git a/hal/src/main/java/edu/wpi/first/hal/NotifierJNI.java b/hal/src/main/java/edu/wpi/first/hal/NotifierJNI.java
index bf92c37..000c7d6 100644
--- a/hal/src/main/java/edu/wpi/first/hal/NotifierJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/NotifierJNI.java
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -20,6 +20,11 @@
   public static native int initializeNotifier();
 
   /**
+   * Sets the name of the notifier.
+   */
+  public static native void setNotifierName(int notifierHandle, String name);
+
+  /**
    * Wakes up the waiter with time=0.  Note: after this function is called, all
    * calls to waitForNotifierAlarm() will immediately start returning 0.
    */
diff --git a/hal/src/main/java/edu/wpi/first/hal/PDPJNI.java b/hal/src/main/java/edu/wpi/first/hal/PDPJNI.java
index c45a053..e2d7fcc 100644
--- a/hal/src/main/java/edu/wpi/first/hal/PDPJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/PDPJNI.java
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -21,6 +21,8 @@
 
   public static native double getPDPChannelCurrent(byte channel, int handle);
 
+  public static native void getPDPAllCurrents(int handle, double[] currents);
+
   public static native double getPDPTotalCurrent(int handle);
 
   public static native double getPDPTotalPower(int handle);
diff --git a/hal/src/main/java/edu/wpi/first/hal/sim/AddressableLEDSim.java b/hal/src/main/java/edu/wpi/first/hal/sim/AddressableLEDSim.java
new file mode 100644
index 0000000..cc6eefa
--- /dev/null
+++ b/hal/src/main/java/edu/wpi/first/hal/sim/AddressableLEDSim.java
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.AddressableLEDDataJNI;
+
+public class AddressableLEDSim {
+  private final int m_index;
+
+  public AddressableLEDSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AddressableLEDDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AddressableLEDDataJNI::cancelInitializedCallback);
+  }
+  public boolean getInitialized() {
+    return AddressableLEDDataJNI.getInitialized(m_index);
+  }
+  public void setInitialized(boolean initialized) {
+    AddressableLEDDataJNI.setInitialized(m_index, initialized);
+  }
+
+  public CallbackStore registerOutputPortCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AddressableLEDDataJNI.registerOutputPortCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AddressableLEDDataJNI::cancelOutputPortCallback);
+  }
+  public int getOutputPort() {
+    return AddressableLEDDataJNI.getOutputPort(m_index);
+  }
+  public void setOutputPort(int outputPort) {
+    AddressableLEDDataJNI.setOutputPort(m_index, outputPort);
+  }
+
+  public CallbackStore registerLengthCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AddressableLEDDataJNI.registerLengthCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AddressableLEDDataJNI::cancelLengthCallback);
+  }
+  public int getLength() {
+    return AddressableLEDDataJNI.getLength(m_index);
+  }
+  public void setLength(int length) {
+    AddressableLEDDataJNI.setLength(m_index, length);
+  }
+
+  public CallbackStore registerRunningCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AddressableLEDDataJNI.registerRunningCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AddressableLEDDataJNI::cancelRunningCallback);
+  }
+  public boolean getRunning() {
+    return AddressableLEDDataJNI.getRunning(m_index);
+  }
+  public void setRunning(boolean running) {
+    AddressableLEDDataJNI.setRunning(m_index, running);
+  }
+
+  public CallbackStore registerDataCallback(ConstBufferCallback callback) {
+    int uid = AddressableLEDDataJNI.registerDataCallback(m_index, callback);
+    return new CallbackStore(m_index, uid, AddressableLEDDataJNI::cancelDataCallback);
+  }
+  public byte[] getData() {
+    return AddressableLEDDataJNI.getData(m_index);
+  }
+  public void setData(byte[] data) {
+    AddressableLEDDataJNI.setData(m_index, data);
+  }
+
+  public void resetData() {
+    AddressableLEDDataJNI.resetData(m_index);
+  }
+}
diff --git a/hal/src/main/java/edu/wpi/first/hal/sim/DutyCycleSim.java b/hal/src/main/java/edu/wpi/first/hal/sim/DutyCycleSim.java
new file mode 100644
index 0000000..9b2806b
--- /dev/null
+++ b/hal/src/main/java/edu/wpi/first/hal/sim/DutyCycleSim.java
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.DutyCycleDataJNI;
+
+public class DutyCycleSim {
+  private final int m_index;
+
+  public DutyCycleSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DutyCycleDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, DutyCycleDataJNI::cancelInitializedCallback);
+  }
+  public boolean getInitialized() {
+    return DutyCycleDataJNI.getInitialized(m_index);
+  }
+  public void setInitialized(boolean initialized) {
+    DutyCycleDataJNI.setInitialized(m_index, initialized);
+  }
+
+  public CallbackStore registerFrequencyCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DutyCycleDataJNI.registerFrequencyCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, DutyCycleDataJNI::cancelFrequencyCallback);
+  }
+  public int getFrequency() {
+    return DutyCycleDataJNI.getFrequency(m_index);
+  }
+  public void setFrequency(int frequency) {
+    DutyCycleDataJNI.setFrequency(m_index, frequency);
+  }
+
+  public CallbackStore registerOutputCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DutyCycleDataJNI.registerOutputCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, DutyCycleDataJNI::cancelOutputCallback);
+  }
+  public double getOutput() {
+    return DutyCycleDataJNI.getOutput(m_index);
+  }
+  public void setOutput(double output) {
+    DutyCycleDataJNI.setOutput(m_index, output);
+  }
+}
diff --git a/hal/src/main/java/edu/wpi/first/hal/sim/NotifierSim.java b/hal/src/main/java/edu/wpi/first/hal/sim/NotifierSim.java
new file mode 100644
index 0000000..f19a674
--- /dev/null
+++ b/hal/src/main/java/edu/wpi/first/hal/sim/NotifierSim.java
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.NotifierDataJNI;
+
+public final class NotifierSim {
+  private NotifierSim() {
+  }
+
+  public static long getNextTimeout() {
+    return NotifierDataJNI.getNextTimeout();
+  }
+
+  public static int getNumNotifiers() {
+    return NotifierDataJNI.getNumNotifiers();
+  }
+}
diff --git a/hal/src/main/java/edu/wpi/first/hal/sim/SimDeviceSim.java b/hal/src/main/java/edu/wpi/first/hal/sim/SimDeviceSim.java
new file mode 100644
index 0000000..e46c811
--- /dev/null
+++ b/hal/src/main/java/edu/wpi/first/hal/sim/SimDeviceSim.java
@@ -0,0 +1,94 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.SimBoolean;
+import edu.wpi.first.hal.SimDouble;
+import edu.wpi.first.hal.SimEnum;
+import edu.wpi.first.hal.SimValue;
+import edu.wpi.first.hal.sim.mockdata.SimDeviceDataJNI;
+
+public class SimDeviceSim {
+  private final int m_handle;
+
+  public SimDeviceSim(String name) {
+    m_handle = SimDeviceDataJNI.getSimDeviceHandle(name);
+  }
+
+  public SimValue getValue(String name) {
+    int handle = SimDeviceDataJNI.getSimValueHandle(m_handle, name);
+    if (handle <= 0) {
+      return null;
+    }
+    return new SimValue(handle);
+  }
+
+  public SimDouble getDouble(String name) {
+    int handle = SimDeviceDataJNI.getSimValueHandle(m_handle, name);
+    if (handle <= 0) {
+      return null;
+    }
+    return new SimDouble(handle);
+  }
+
+  public SimEnum getEnum(String name) {
+    int handle = SimDeviceDataJNI.getSimValueHandle(m_handle, name);
+    if (handle <= 0) {
+      return null;
+    }
+    return new SimEnum(handle);
+  }
+
+  public SimBoolean getBoolean(String name) {
+    int handle = SimDeviceDataJNI.getSimValueHandle(m_handle, name);
+    if (handle <= 0) {
+      return null;
+    }
+    return new SimBoolean(handle);
+  }
+
+  public static String[] getEnumOptions(SimEnum val) {
+    return SimDeviceDataJNI.getSimValueEnumOptions(val.getNativeHandle());
+  }
+
+  public SimDeviceDataJNI.SimValueInfo[] enumerateValues() {
+    return SimDeviceDataJNI.enumerateSimValues(m_handle);
+  }
+
+  public int getNativeHandle() {
+    return m_handle;
+  }
+
+  public CallbackStore registerValueCreatedCallback(SimValueCallback callback, boolean initialNotify) {
+    int uid = SimDeviceDataJNI.registerSimValueCreatedCallback(m_handle, callback, initialNotify);
+    return new CallbackStore(uid, SimDeviceDataJNI::cancelSimValueCreatedCallback);
+  }
+
+  public CallbackStore registerValueChangedCallback(SimValueCallback callback, boolean initialNotify) {
+    int uid = SimDeviceDataJNI.registerSimValueChangedCallback(m_handle, callback, initialNotify);
+    return new CallbackStore(uid, SimDeviceDataJNI::cancelSimValueChangedCallback);
+  }
+
+  public static SimDeviceDataJNI.SimDeviceInfo[] enumerateDevices(String prefix) {
+    return SimDeviceDataJNI.enumerateSimDevices(prefix);
+  }
+
+  public CallbackStore registerDeviceCreatedCallback(String prefix, SimDeviceCallback callback, boolean initialNotify) {
+    int uid = SimDeviceDataJNI.registerSimDeviceCreatedCallback(prefix, callback, initialNotify);
+    return new CallbackStore(uid, SimDeviceDataJNI::cancelSimDeviceCreatedCallback);
+  }
+
+  public CallbackStore registerDeviceFreedCallback(String prefix, SimDeviceCallback callback) {
+    int uid = SimDeviceDataJNI.registerSimDeviceFreedCallback(prefix, callback);
+    return new CallbackStore(uid, SimDeviceDataJNI::cancelSimDeviceFreedCallback);
+  }
+
+  public static void resetData() {
+    SimDeviceDataJNI.resetSimDeviceData();
+  }
+}
diff --git a/hal/src/main/java/edu/wpi/first/hal/sim/SimHooks.java b/hal/src/main/java/edu/wpi/first/hal/sim/SimHooks.java
index 6c46111..9805497 100644
--- a/hal/src/main/java/edu/wpi/first/hal/sim/SimHooks.java
+++ b/hal/src/main/java/edu/wpi/first/hal/sim/SimHooks.java
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* 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.                                                               */
@@ -24,4 +24,20 @@
   public static void restartTiming() {
     SimulatorJNI.restartTiming();
   }
+
+  public static void pauseTiming() {
+    SimulatorJNI.pauseTiming();
+  }
+
+  public static void resumeTiming() {
+    SimulatorJNI.resumeTiming();
+  }
+
+  public static boolean isTimingPaused() {
+    return SimulatorJNI.isTimingPaused();
+  }
+
+  public static void stepTiming(long delta) {
+    SimulatorJNI.stepTiming(delta);
+  }
 }
diff --git a/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AddressableLEDDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AddressableLEDDataJNI.java
new file mode 100644
index 0000000..8098e68
--- /dev/null
+++ b/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AddressableLEDDataJNI.java
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.ConstBufferCallback;
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class AddressableLEDDataJNI extends JNIWrapper {
+  public static native int registerInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedCallback(int index, int uid);
+  public static native boolean getInitialized(int index);
+  public static native void setInitialized(int index, boolean initialized);
+
+  public static native int registerOutputPortCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelOutputPortCallback(int index, int uid);
+  public static native int getOutputPort(int index);
+  public static native void setOutputPort(int index, int outputPort);
+
+  public static native int registerLengthCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelLengthCallback(int index, int uid);
+  public static native int getLength(int index);
+  public static native void setLength(int index, int length);
+
+  public static native int registerRunningCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelRunningCallback(int index, int uid);
+  public static native boolean getRunning(int index);
+  public static native void setRunning(int index, boolean running);
+
+  public static native int registerDataCallback(int index, ConstBufferCallback callback);
+  public static native void cancelDataCallback(int index, int uid);
+  public static native byte[] getData(int index);
+  public static native void setData(int index, byte[] data);
+
+  public static native void resetData(int index);
+}
diff --git a/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DutyCycleDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DutyCycleDataJNI.java
new file mode 100644
index 0000000..5cbae6e
--- /dev/null
+++ b/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DutyCycleDataJNI.java
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class DutyCycleDataJNI extends JNIWrapper {
+  public static native int registerInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedCallback(int index, int uid);
+  public static native boolean getInitialized(int index);
+  public static native void setInitialized(int index, boolean initialized);
+
+  public static native int registerFrequencyCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelFrequencyCallback(int index, int uid);
+  public static native int getFrequency(int index);
+  public static native void setFrequency(int index, int frequency);
+
+  public static native int registerOutputCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelOutputCallback(int index, int uid);
+  public static native double getOutput(int index);
+  public static native void setOutput(int index, double output);
+
+  public static native void resetData(int index);
+}
diff --git a/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/NotifierDataJNI.java b/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/NotifierDataJNI.java
new file mode 100644
index 0000000..ecc0842
--- /dev/null
+++ b/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/NotifierDataJNI.java
@@ -0,0 +1,15 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.JNIWrapper;
+
+public class NotifierDataJNI extends JNIWrapper {
+  public static native long getNextTimeout();
+  public static native int getNumNotifiers();
+}
diff --git a/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/SimulatorJNI.java b/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/SimulatorJNI.java
index bb86005..bfd8505 100644
--- a/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/SimulatorJNI.java
+++ b/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/SimulatorJNI.java
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2018 FIRST. All Rights Reserved.                             */
+/* 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.                                                               */
@@ -13,5 +13,9 @@
   public static native void waitForProgramStart();
   public static native void setProgramStarted();
   public static native void restartTiming();
+  public static native void pauseTiming();
+  public static native void resumeTiming();
+  public static native boolean isTimingPaused();
+  public static native void stepTiming(long delta);
   public static native void resetHandles();
 }
diff --git a/hal/src/main/native/athena/AddressableLED.cpp b/hal/src/main/native/athena/AddressableLED.cpp
new file mode 100644
index 0000000..9ecc4c4
--- /dev/null
+++ b/hal/src/main/native/athena/AddressableLED.cpp
@@ -0,0 +1,286 @@
+/*----------------------------------------------------------------------------*/
+/* 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/AddressableLED.h"
+
+#include <cstring>
+
+#include "ConstantsInternal.h"
+#include "DigitalInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/ChipObject.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+
+using namespace hal;
+
+extern "C" {
+NiFpga_Status NiFpga_ClientFunctionCall(NiFpga_Session session, uint32_t group,
+                                        uint32_t functionId,
+                                        const void* inBuffer,
+                                        size_t inBufferSize, void* outBuffer,
+                                        size_t outBufferSize);
+}  // extern "C"
+
+namespace {
+struct AddressableLED {
+  std::unique_ptr<tLED> led;
+  void* ledBuffer;
+  size_t ledBufferSize;
+  int32_t stringLength = 1;
+};
+}  // namespace
+
+static LimitedHandleResource<
+    HAL_AddressableLEDHandle, AddressableLED, kNumAddressableLEDs,
+    HAL_HandleEnum::AddressableLED>* addressableLEDHandles;
+
+namespace hal {
+namespace init {
+void InitializeAddressableLED() {
+  static LimitedHandleResource<HAL_AddressableLEDHandle, AddressableLED,
+                               kNumAddressableLEDs,
+                               HAL_HandleEnum::AddressableLED>
+      alH;
+  addressableLEDHandles = &alH;
+}
+}  // namespace init
+}  // namespace hal
+
+// Shim for broken ChipObject function
+static const uint32_t clientFeature_hostMemoryBuffer = 0;
+static const uint32_t hostMemoryBufferFunction_open = 2;
+
+// Input arguments for HMB open
+struct AtomicHMBOpenInputs {
+  const char* memoryName;
+};
+
+// Output arguments for HMB open
+struct AtomicHMBOpenOutputs {
+  size_t size;
+  void* virtualAddress;
+};
+
+static NiFpga_Status OpenHostMemoryBuffer(NiFpga_Session session,
+                                          const char* memoryName,
+                                          void** virtualAddress, size_t* size) {
+  struct AtomicHMBOpenOutputs outputs;
+
+  struct AtomicHMBOpenInputs inputs;
+  inputs.memoryName = memoryName;
+
+  NiFpga_Status retval = NiFpga_ClientFunctionCall(
+      session, clientFeature_hostMemoryBuffer, hostMemoryBufferFunction_open,
+      &inputs, sizeof(struct AtomicHMBOpenInputs), &outputs,
+      sizeof(struct AtomicHMBOpenOutputs));
+  if (NiFpga_IsError(retval)) {
+    return retval;
+  }
+  *virtualAddress = outputs.virtualAddress;
+  if (size != NULL) {
+    *size = outputs.size;
+  }
+  return retval;
+}
+
+extern "C" {
+
+HAL_AddressableLEDHandle HAL_InitializeAddressableLED(
+    HAL_DigitalHandle outputPort, int32_t* status) {
+  hal::init::CheckInit();
+
+  auto digitalPort =
+      hal::digitalChannelHandles->Get(outputPort, hal::HAL_HandleEnum::PWM);
+
+  if (!digitalPort) {
+    // If DIO was passed, channel error, else generic error
+    if (getHandleType(outputPort) == hal::HAL_HandleEnum::DIO) {
+      *status = HAL_LED_CHANNEL_ERROR;
+    } else {
+      *status = HAL_HANDLE_ERROR;
+    }
+    return HAL_kInvalidHandle;
+  }
+
+  if (digitalPort->channel >= kNumPWMHeaders) {
+    *status = HAL_LED_CHANNEL_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  auto handle = addressableLEDHandles->Allocate();
+
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+
+  auto led = addressableLEDHandles->Get(handle);
+
+  if (!led) {
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  led->led.reset(tLED::create(status));
+
+  if (*status != 0) {
+    addressableLEDHandles->Free(handle);
+    return HAL_kInvalidHandle;
+  }
+
+  led->led->writeOutputSelect(digitalPort->channel, status);
+
+  if (*status != 0) {
+    addressableLEDHandles->Free(handle);
+    return HAL_kInvalidHandle;
+  }
+
+  led->ledBuffer = nullptr;
+  led->ledBufferSize = 0;
+
+  uint32_t session = led->led->getSystemInterface()->getHandle();
+
+  *status = OpenHostMemoryBuffer(session, "HMB_0_LED", &led->ledBuffer,
+                                 &led->ledBufferSize);
+
+  if (*status != 0) {
+    addressableLEDHandles->Free(handle);
+    return HAL_kInvalidHandle;
+  }
+
+  return handle;
+}
+
+void HAL_FreeAddressableLED(HAL_AddressableLEDHandle handle) {
+  addressableLEDHandles->Free(handle);
+}
+
+void HAL_SetAddressableLEDOutputPort(HAL_AddressableLEDHandle handle,
+                                     HAL_DigitalHandle outputPort,
+                                     int32_t* status) {
+  auto digitalPort =
+      hal::digitalChannelHandles->Get(outputPort, hal::HAL_HandleEnum::PWM);
+
+  if (!digitalPort) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  auto led = addressableLEDHandles->Get(handle);
+  if (!led) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  led->led->writeOutputSelect(digitalPort->channel, status);
+}
+
+void HAL_SetAddressableLEDLength(HAL_AddressableLEDHandle handle,
+                                 int32_t length, int32_t* status) {
+  auto led = addressableLEDHandles->Get(handle);
+  if (!led) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (length > HAL_kAddressableLEDMaxLength) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+
+  led->led->strobeReset(status);
+
+  while (led->led->readPixelWriteIndex(status) != 0) {
+  }
+
+  if (*status != 0) {
+    return;
+  }
+
+  led->led->writeStringLength(length, status);
+
+  led->stringLength = length;
+}
+
+static_assert(sizeof(HAL_AddressableLEDData) == sizeof(uint32_t),
+              "LED Data must be 32 bit");
+
+void HAL_WriteAddressableLEDData(HAL_AddressableLEDHandle handle,
+                                 const struct HAL_AddressableLEDData* data,
+                                 int32_t length, int32_t* status) {
+  auto led = addressableLEDHandles->Get(handle);
+  if (!led) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (length > led->stringLength) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+
+  std::memcpy(led->ledBuffer, data, length * sizeof(HAL_AddressableLEDData));
+
+  asm("dmb");
+
+  led->led->strobeLoad(status);
+}
+
+void HAL_SetAddressableLEDBitTiming(HAL_AddressableLEDHandle handle,
+                                    int32_t lowTime0NanoSeconds,
+                                    int32_t highTime0NanoSeconds,
+                                    int32_t lowTime1NanoSeconds,
+                                    int32_t highTime1NanoSeconds,
+                                    int32_t* status) {
+  auto led = addressableLEDHandles->Get(handle);
+  if (!led) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  led->led->writeLowBitTickTiming(1, highTime0NanoSeconds / 25, status);
+  led->led->writeLowBitTickTiming(0, lowTime0NanoSeconds / 25, status);
+  led->led->writeHighBitTickTiming(1, highTime1NanoSeconds / 25, status);
+  led->led->writeHighBitTickTiming(0, lowTime1NanoSeconds / 25, status);
+}
+
+void HAL_SetAddressableLEDSyncTime(HAL_AddressableLEDHandle handle,
+                                   int32_t syncTimeMicroSeconds,
+                                   int32_t* status) {
+  auto led = addressableLEDHandles->Get(handle);
+  if (!led) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  led->led->writeSyncTiming(syncTimeMicroSeconds, status);
+}
+
+void HAL_StartAddressableLEDOutput(HAL_AddressableLEDHandle handle,
+                                   int32_t* status) {
+  auto led = addressableLEDHandles->Get(handle);
+  if (!led) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  led->led->strobeStart(status);
+}
+
+void HAL_StopAddressableLEDOutput(HAL_AddressableLEDHandle handle,
+                                  int32_t* status) {
+  auto led = addressableLEDHandles->Get(handle);
+  if (!led) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  led->led->strobeAbort(status);
+}
+}  // extern "C"
diff --git a/hal/src/main/native/athena/AnalogGyro.cpp b/hal/src/main/native/athena/AnalogGyro.cpp
index 56b6f28..12d688d 100644
--- a/hal/src/main/native/athena/AnalogGyro.cpp
+++ b/hal/src/main/native/athena/AnalogGyro.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -181,7 +181,7 @@
   if (*status != 0) return;
 
   gyro->center = static_cast<int32_t>(
-      static_cast<double>(value) / static_cast<double>(count) + .5);
+      static_cast<double>(value) / static_cast<double>(count) + 0.5);
 
   gyro->offset = static_cast<double>(value) / static_cast<double>(count) -
                  static_cast<double>(gyro->center);
diff --git a/hal/src/main/native/athena/AnalogInput.cpp b/hal/src/main/native/athena/AnalogInput.cpp
index 859524e..1d502b9 100644
--- a/hal/src/main/native/athena/AnalogInput.cpp
+++ b/hal/src/main/native/athena/AnalogInput.cpp
@@ -201,6 +201,14 @@
   return voltage;
 }
 
+double HAL_GetAnalogValueToVolts(HAL_AnalogInputHandle analogPortHandle,
+                                 int32_t rawValue, int32_t* status) {
+  int32_t LSBWeight = HAL_GetAnalogLSBWeight(analogPortHandle, status);
+  int32_t offset = HAL_GetAnalogOffset(analogPortHandle, status);
+  double voltage = LSBWeight * 1.0e-9 * rawValue - offset * 1.0e-9;
+  return voltage;
+}
+
 double HAL_GetAnalogAverageVoltage(HAL_AnalogInputHandle analogPortHandle,
                                    int32_t* status) {
   int32_t value = HAL_GetAnalogAverageValue(analogPortHandle, status);
@@ -216,26 +224,38 @@
 
 int32_t HAL_GetAnalogLSBWeight(HAL_AnalogInputHandle analogPortHandle,
                                int32_t* status) {
-  auto port = analogInputHandles->Get(analogPortHandle);
-  if (port == nullptr) {
-    *status = HAL_HANDLE_ERROR;
-    return 0;
-  }
-  int32_t lsbWeight = FRC_NetworkCommunication_nAICalibration_getLSBWeight(
-      0, port->channel, status);  // XXX: aiSystemIndex == 0?
-  return lsbWeight;
+  // On the roboRIO, LSB is the same for all channels. So the channel lookup can
+  // be avoided
+  return FRC_NetworkCommunication_nAICalibration_getLSBWeight(0, 0, status);
+
+  // Keep the old code for future hardware
+
+  // auto port = analogInputHandles->Get(analogPortHandle);
+  // if (port == nullptr) {
+  //   *status = HAL_HANDLE_ERROR;
+  //   return 0;
+  // }
+  // int32_t lsbWeight = FRC_NetworkCommunication_nAICalibration_getLSBWeight(
+  //     0, port->channel, status);  // XXX: aiSystemIndex == 0?
+  // return lsbWeight;
 }
 
 int32_t HAL_GetAnalogOffset(HAL_AnalogInputHandle analogPortHandle,
                             int32_t* status) {
-  auto port = analogInputHandles->Get(analogPortHandle);
-  if (port == nullptr) {
-    *status = HAL_HANDLE_ERROR;
-    return 0;
-  }
-  int32_t offset = FRC_NetworkCommunication_nAICalibration_getOffset(
-      0, port->channel, status);  // XXX: aiSystemIndex == 0?
-  return offset;
+  // On the roboRIO, offset is the same for all channels. So the channel lookup
+  // can be avoided
+  return FRC_NetworkCommunication_nAICalibration_getOffset(0, 0, status);
+
+  // Keep the old code for future hardware
+
+  // auto port = analogInputHandles->Get(analogPortHandle);
+  // if (port == nullptr) {
+  //   *status = HAL_HANDLE_ERROR;
+  //   return 0;
+  // }
+  // int32_t offset = FRC_NetworkCommunication_nAICalibration_getOffset(
+  //     0, port->channel, status);  // XXX: aiSystemIndex == 0?
+  // return offset;
 }
 
 }  // extern "C"
diff --git a/hal/src/main/native/athena/AnalogTrigger.cpp b/hal/src/main/native/athena/AnalogTrigger.cpp
index 1841c51..9ec3f29 100644
--- a/hal/src/main/native/athena/AnalogTrigger.cpp
+++ b/hal/src/main/native/athena/AnalogTrigger.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -8,9 +8,11 @@
 #include "hal/AnalogTrigger.h"
 
 #include "AnalogInternal.h"
+#include "DutyCycleInternal.h"
 #include "HALInitializer.h"
 #include "PortsInternal.h"
 #include "hal/AnalogInput.h"
+#include "hal/DutyCycle.h"
 #include "hal/Errors.h"
 #include "hal/handles/HandlesInternal.h"
 #include "hal/handles/LimitedHandleResource.h"
@@ -21,7 +23,7 @@
 
 struct AnalogTrigger {
   std::unique_ptr<tAnalogTrigger> trigger;
-  HAL_AnalogInputHandle analogHandle;
+  HAL_Handle handle;
   uint8_t index;
 };
 
@@ -46,7 +48,7 @@
 extern "C" {
 
 HAL_AnalogTriggerHandle HAL_InitializeAnalogTrigger(
-    HAL_AnalogInputHandle portHandle, int32_t* index, int32_t* status) {
+    HAL_AnalogInputHandle portHandle, int32_t* status) {
   hal::init::CheckInit();
   // ensure we are given a valid and active AnalogInput handle
   auto analog_port = analogInputHandles->Get(portHandle);
@@ -64,19 +66,46 @@
     *status = HAL_HANDLE_ERROR;
     return HAL_kInvalidHandle;
   }
-  trigger->analogHandle = portHandle;
+  trigger->handle = portHandle;
   trigger->index = static_cast<uint8_t>(getHandleIndex(handle));
-  *index = trigger->index;
 
   trigger->trigger.reset(tAnalogTrigger::create(trigger->index, status));
   trigger->trigger->writeSourceSelect_Channel(analog_port->channel, status);
   return handle;
 }
 
+HAL_AnalogTriggerHandle HAL_InitializeAnalogTriggerDutyCycle(
+    HAL_DutyCycleHandle dutyCycleHandle, int32_t* status) {
+  hal::init::CheckInit();
+  // ensure we are given a valid and active DutyCycle handle
+  auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);
+  if (dutyCycle == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  HAL_AnalogTriggerHandle handle = analogTriggerHandles->Allocate();
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+  auto trigger = analogTriggerHandles->Get(handle);
+  if (trigger == nullptr) {  // would only occur on thread issue
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  trigger->handle = dutyCycleHandle;
+  trigger->index = static_cast<uint8_t>(getHandleIndex(handle));
+
+  trigger->trigger.reset(tAnalogTrigger::create(trigger->index, status));
+  trigger->trigger->writeSourceSelect_Channel(dutyCycle->index, status);
+  trigger->trigger->writeSourceSelect_DutyCycle(true, status);
+  return handle;
+}
+
 void HAL_CleanAnalogTrigger(HAL_AnalogTriggerHandle analogTriggerHandle,
                             int32_t* status) {
   analogTriggerHandles->Free(analogTriggerHandle);
-  // caller owns the analog input handle.
+  // caller owns the input handle.
 }
 
 void HAL_SetAnalogTriggerLimitsRaw(HAL_AnalogTriggerHandle analogTriggerHandle,
@@ -89,11 +118,46 @@
   }
   if (lower > upper) {
     *status = ANALOG_TRIGGER_LIMIT_ORDER_ERROR;
+    return;
   }
   trigger->trigger->writeLowerLimit(lower, status);
   trigger->trigger->writeUpperLimit(upper, status);
 }
 
+void HAL_SetAnalogTriggerLimitsDutyCycle(
+    HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper,
+    int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (getHandleType(trigger->handle) != HAL_HandleEnum::DutyCycle) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (lower > upper) {
+    *status = ANALOG_TRIGGER_LIMIT_ORDER_ERROR;
+    return;
+  }
+
+  if (lower < 0.0 || upper > 1.0) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+
+  int32_t scaleFactor =
+      HAL_GetDutyCycleOutputScaleFactor(trigger->handle, status);
+  if (*status != 0) {
+    return;
+  }
+
+  trigger->trigger->writeLowerLimit(static_cast<int32_t>(scaleFactor * lower),
+                                    status);
+  trigger->trigger->writeUpperLimit(static_cast<int32_t>(scaleFactor * upper),
+                                    status);
+}
+
 void HAL_SetAnalogTriggerLimitsVoltage(
     HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper,
     int32_t* status) {
@@ -102,16 +166,22 @@
     *status = HAL_HANDLE_ERROR;
     return;
   }
+
+  if (getHandleType(trigger->handle) != HAL_HandleEnum::AnalogInput) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
   if (lower > upper) {
     *status = ANALOG_TRIGGER_LIMIT_ORDER_ERROR;
+    return;
   }
 
   // TODO: This depends on the averaged setting.  Only raw values will work as
   // is.
   trigger->trigger->writeLowerLimit(
-      HAL_GetAnalogVoltsToValue(trigger->analogHandle, lower, status), status);
+      HAL_GetAnalogVoltsToValue(trigger->handle, lower, status), status);
   trigger->trigger->writeUpperLimit(
-      HAL_GetAnalogVoltsToValue(trigger->analogHandle, upper, status), status);
+      HAL_GetAnalogVoltsToValue(trigger->handle, upper, status), status);
 }
 
 void HAL_SetAnalogTriggerAveraged(HAL_AnalogTriggerHandle analogTriggerHandle,
@@ -121,7 +191,8 @@
     *status = HAL_HANDLE_ERROR;
     return;
   }
-  if (trigger->trigger->readSourceSelect_Filter(status) != 0) {
+  if (trigger->trigger->readSourceSelect_Filter(status) != 0 ||
+      trigger->trigger->readSourceSelect_DutyCycle(status) != 0) {
     *status = INCOMPATIBLE_STATE;
     // TODO: wpi_setWPIErrorWithContext(IncompatibleMode, "Hardware does not
     // support average and filtering at the same time.");
@@ -136,7 +207,8 @@
     *status = HAL_HANDLE_ERROR;
     return;
   }
-  if (trigger->trigger->readSourceSelect_Averaged(status) != 0) {
+  if (trigger->trigger->readSourceSelect_Averaged(status) != 0 ||
+      trigger->trigger->readSourceSelect_DutyCycle(status) != 0) {
     *status = INCOMPATIBLE_STATE;
     // TODO: wpi_setWPIErrorWithContext(IncompatibleMode, "Hardware does not "
     // "support average and filtering at the same time.");
@@ -177,16 +249,27 @@
     case HAL_Trigger_kInWindow:
       result =
           trigger->trigger->readOutput_InHysteresis(trigger->index, status);
-      break;  // XXX: Backport
+      break;
     case HAL_Trigger_kState:
       result = trigger->trigger->readOutput_OverLimit(trigger->index, status);
-      break;  // XXX: Backport
+      break;
     case HAL_Trigger_kRisingPulse:
     case HAL_Trigger_kFallingPulse:
       *status = ANALOG_TRIGGER_PULSE_OUTPUT_ERROR;
       return false;
+      break;
   }
   return result;
 }
 
+int32_t HAL_GetAnalogTriggerFPGAIndex(
+    HAL_AnalogTriggerHandle analogTriggerHandle, int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+  return trigger->index;
+}
+
 }  // extern "C"
diff --git a/hal/src/main/native/athena/DMA.cpp b/hal/src/main/native/athena/DMA.cpp
new file mode 100644
index 0000000..ee39d2d
--- /dev/null
+++ b/hal/src/main/native/athena/DMA.cpp
@@ -0,0 +1,1006 @@
+/*----------------------------------------------------------------------------*/
+/* 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/DMA.h"
+
+#include <array>
+#include <cstddef>
+#include <cstring>
+#include <memory>
+#include <type_traits>
+
+#include "AnalogInternal.h"
+#include "DigitalInternal.h"
+#include "EncoderInternal.h"
+#include "PortsInternal.h"
+#include "hal/AnalogAccumulator.h"
+#include "hal/AnalogGyro.h"
+#include "hal/AnalogInput.h"
+#include "hal/ChipObject.h"
+#include "hal/Errors.h"
+#include "hal/HALBase.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+#include "hal/handles/UnlimitedHandleResource.h"
+
+using namespace hal;
+
+static_assert(std::is_standard_layout_v<HAL_DMASample>,
+              "HAL_DMASample must have standard layout");
+
+namespace {
+
+struct DMA {
+  std::unique_ptr<tDMAManager> manager;
+  std::unique_ptr<tDMA> aDMA;
+
+  HAL_DMASample captureStore;
+};
+}  // namespace
+
+static constexpr size_t kChannelSize[22] = {2, 2, 4, 4, 2, 2, 4, 4, 3, 3, 2,
+                                            1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4};
+
+enum DMAOffsetConstants {
+  kEnable_AI0_Low = 0,
+  kEnable_AI0_High = 1,
+  kEnable_AIAveraged0_Low = 2,
+  kEnable_AIAveraged0_High = 3,
+  kEnable_AI1_Low = 4,
+  kEnable_AI1_High = 5,
+  kEnable_AIAveraged1_Low = 6,
+  kEnable_AIAveraged1_High = 7,
+  kEnable_Accumulator0 = 8,
+  kEnable_Accumulator1 = 9,
+  kEnable_DI = 10,
+  kEnable_AnalogTriggers = 11,
+  kEnable_Counters_Low = 12,
+  kEnable_Counters_High = 13,
+  kEnable_CounterTimers_Low = 14,
+  kEnable_CounterTimers_High = 15,
+  kEnable_Encoders_Low = 16,
+  kEnable_Encoders_High = 17,
+  kEnable_EncoderTimers_Low = 18,
+  kEnable_EncoderTimers_High = 19,
+  kEnable_DutyCycle_Low = 20,
+  kEnable_DutyCycle_High = 21,
+};
+
+static hal::LimitedHandleResource<HAL_DMAHandle, DMA, 1, HAL_HandleEnum::DMA>*
+    dmaHandles;
+
+namespace hal {
+namespace init {
+void InitializeDMA() {
+  static hal::LimitedHandleResource<HAL_DMAHandle, DMA, 1, HAL_HandleEnum::DMA>
+      dH;
+  dmaHandles = &dH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_DMAHandle HAL_InitializeDMA(int32_t* status) {
+  HAL_Handle handle = dmaHandles->Allocate();
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+
+  auto dma = dmaHandles->Get(handle);
+
+  if (!dma) {
+    // Can only happen on thread error
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  // Manager does not get created until DMA is started
+  dma->aDMA.reset(tDMA::create(status));
+  if (*status != 0) {
+    dmaHandles->Free(handle);
+    return HAL_kInvalidHandle;
+  }
+
+  dma->aDMA->writeConfig_ExternalClock(false, status);
+  if (*status != 0) {
+    dmaHandles->Free(handle);
+    return HAL_kInvalidHandle;
+  }
+
+  HAL_SetDMARate(handle, 1, status);
+  if (*status != 0) {
+    dmaHandles->Free(handle);
+    return HAL_kInvalidHandle;
+  }
+
+  HAL_SetDMAPause(handle, false, status);
+  return handle;
+}
+
+void HAL_FreeDMA(HAL_DMAHandle handle) {
+  auto dma = dmaHandles->Get(handle);
+  dmaHandles->Free(handle);
+
+  if (!dma) return;
+
+  int32_t status = 0;
+  if (dma->manager) {
+    dma->manager->stop(&status);
+  }
+}
+
+void HAL_SetDMAPause(HAL_DMAHandle handle, HAL_Bool pause, int32_t* status) {
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  dma->aDMA->writeConfig_Pause(pause, status);
+}
+void HAL_SetDMARate(HAL_DMAHandle handle, int32_t cycles, int32_t* status) {
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (cycles < 1) {
+    cycles = 1;
+  }
+
+  dma->aDMA->writeRate(static_cast<uint32_t>(cycles), status);
+}
+
+void HAL_AddDMAEncoder(HAL_DMAHandle handle, HAL_EncoderHandle encoderHandle,
+                       int32_t* status) {
+  // Detect a counter encoder vs an actual encoder, and use the right DMA calls
+  HAL_FPGAEncoderHandle fpgaEncoderHandle = HAL_kInvalidHandle;
+  HAL_CounterHandle counterHandle = HAL_kInvalidHandle;
+
+  bool validEncoderHandle = hal::GetEncoderBaseHandle(
+      encoderHandle, &fpgaEncoderHandle, &counterHandle);
+
+  if (!validEncoderHandle) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (counterHandle != HAL_kInvalidHandle) {
+    HAL_AddDMACounter(handle, counterHandle, status);
+    return;
+  }
+
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (dma->manager) {
+    *status = HAL_INVALID_DMA_ADDITION;
+    return;
+  }
+
+  if (getHandleType(fpgaEncoderHandle) != HAL_HandleEnum::FPGAEncoder) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  int32_t index = getHandleIndex(fpgaEncoderHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (index < 4) {
+    dma->aDMA->writeConfig_Enable_Encoders_Low(true, status);
+  } else if (index < 8) {
+    dma->aDMA->writeConfig_Enable_Encoders_High(true, status);
+  } else {
+    *status = NiFpga_Status_InvalidParameter;
+  }
+}
+
+void HAL_AddDMAEncoderPeriod(HAL_DMAHandle handle,
+                             HAL_EncoderHandle encoderHandle, int32_t* status) {
+  // Detect a counter encoder vs an actual encoder, and use the right DMA calls
+  HAL_FPGAEncoderHandle fpgaEncoderHandle = HAL_kInvalidHandle;
+  HAL_CounterHandle counterHandle = HAL_kInvalidHandle;
+
+  bool validEncoderHandle = hal::GetEncoderBaseHandle(
+      encoderHandle, &fpgaEncoderHandle, &counterHandle);
+
+  if (!validEncoderHandle) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (counterHandle != HAL_kInvalidHandle) {
+    HAL_AddDMACounterPeriod(handle, counterHandle, status);
+    return;
+  }
+
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (dma->manager) {
+    *status = HAL_INVALID_DMA_ADDITION;
+    return;
+  }
+
+  if (getHandleType(fpgaEncoderHandle) != HAL_HandleEnum::FPGAEncoder) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  int32_t index = getHandleIndex(fpgaEncoderHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (index < 4) {
+    dma->aDMA->writeConfig_Enable_EncoderTimers_Low(true, status);
+  } else if (index < 8) {
+    dma->aDMA->writeConfig_Enable_EncoderTimers_High(true, status);
+  } else {
+    *status = NiFpga_Status_InvalidParameter;
+  }
+}
+
+void HAL_AddDMACounter(HAL_DMAHandle handle, HAL_CounterHandle counterHandle,
+                       int32_t* status) {
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (dma->manager) {
+    *status = HAL_INVALID_DMA_ADDITION;
+    return;
+  }
+
+  if (getHandleType(counterHandle) != HAL_HandleEnum::Counter) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  int32_t index = getHandleIndex(counterHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (index < 4) {
+    dma->aDMA->writeConfig_Enable_Counters_Low(true, status);
+  } else if (index < 8) {
+    dma->aDMA->writeConfig_Enable_Counters_High(true, status);
+  } else {
+    *status = NiFpga_Status_InvalidParameter;
+  }
+}
+
+void HAL_AddDMACounterPeriod(HAL_DMAHandle handle,
+                             HAL_CounterHandle counterHandle, int32_t* status) {
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (dma->manager) {
+    *status = HAL_INVALID_DMA_ADDITION;
+    return;
+  }
+
+  if (getHandleType(counterHandle) != HAL_HandleEnum::Counter) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  int32_t index = getHandleIndex(counterHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (index < 4) {
+    dma->aDMA->writeConfig_Enable_CounterTimers_Low(true, status);
+  } else if (index < 8) {
+    dma->aDMA->writeConfig_Enable_CounterTimers_High(true, status);
+  } else {
+    *status = NiFpga_Status_InvalidParameter;
+  }
+}
+
+void HAL_AddDMADigitalSource(HAL_DMAHandle handle,
+                             HAL_Handle digitalSourceHandle, int32_t* status) {
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (dma->manager) {
+    *status = HAL_INVALID_DMA_ADDITION;
+    return;
+  }
+
+  if (isHandleType(digitalSourceHandle, HAL_HandleEnum::AnalogTrigger)) {
+    dma->aDMA->writeConfig_Enable_AnalogTriggers(true, status);
+  } else if (isHandleType(digitalSourceHandle, HAL_HandleEnum::DIO)) {
+    dma->aDMA->writeConfig_Enable_DI(true, status);
+  } else {
+    *status = NiFpga_Status_InvalidParameter;
+  }
+}
+
+void HAL_AddDMAAnalogInput(HAL_DMAHandle handle,
+                           HAL_AnalogInputHandle aInHandle, int32_t* status) {
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (dma->manager) {
+    *status = HAL_INVALID_DMA_ADDITION;
+    return;
+  }
+
+  if (getHandleType(aInHandle) != HAL_HandleEnum::AnalogInput) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  int32_t index = getHandleIndex(aInHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (index < 4) {
+    dma->aDMA->writeConfig_Enable_AI0_Low(true, status);
+  } else if (index < 8) {
+    dma->aDMA->writeConfig_Enable_AI0_High(true, status);
+  } else {
+    *status = NiFpga_Status_InvalidParameter;
+  }
+}
+
+void HAL_AddDMADutyCycle(HAL_DMAHandle handle,
+                         HAL_DutyCycleHandle dutyCycleHandle, int32_t* status) {
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (dma->manager) {
+    *status = HAL_INVALID_DMA_ADDITION;
+    return;
+  }
+
+  if (getHandleType(dutyCycleHandle) != HAL_HandleEnum::DutyCycle) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  int32_t index = getHandleIndex(dutyCycleHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (index < 4) {
+    dma->aDMA->writeConfig_Enable_DutyCycle_Low(true, status);
+  } else if (index < 8) {
+    dma->aDMA->writeConfig_Enable_DutyCycle_High(true, status);
+  } else {
+    *status = NiFpga_Status_InvalidParameter;
+  }
+}
+
+void HAL_AddDMAAveragedAnalogInput(HAL_DMAHandle handle,
+                                   HAL_AnalogInputHandle aInHandle,
+                                   int32_t* status) {
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (dma->manager) {
+    *status = HAL_INVALID_DMA_ADDITION;
+    return;
+  }
+
+  if (getHandleType(aInHandle) != HAL_HandleEnum::AnalogInput) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  int32_t index = getHandleIndex(aInHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (index < 4) {
+    dma->aDMA->writeConfig_Enable_AIAveraged0_Low(true, status);
+  } else if (index < 8) {
+    dma->aDMA->writeConfig_Enable_AIAveraged0_High(true, status);
+  } else {
+    *status = NiFpga_Status_InvalidParameter;
+  }
+}
+
+void HAL_AddDMAAnalogAccumulator(HAL_DMAHandle handle,
+                                 HAL_AnalogInputHandle aInHandle,
+                                 int32_t* status) {
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (dma->manager) {
+    *status = HAL_INVALID_DMA_ADDITION;
+    return;
+  }
+
+  if (!HAL_IsAccumulatorChannel(aInHandle, status)) {
+    *status = HAL_INVALID_ACCUMULATOR_CHANNEL;
+    return;
+  }
+
+  int32_t index = getHandleIndex(aInHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (index == 0) {
+    dma->aDMA->writeConfig_Enable_Accumulator0(true, status);
+  } else if (index == 1) {
+    dma->aDMA->writeConfig_Enable_Accumulator1(true, status);
+  } else {
+    *status = NiFpga_Status_InvalidParameter;
+  }
+}
+
+void HAL_SetDMAExternalTrigger(HAL_DMAHandle handle,
+                               HAL_Handle digitalSourceHandle,
+                               HAL_AnalogTriggerType analogTriggerType,
+                               HAL_Bool rising, HAL_Bool falling,
+                               int32_t* status) {
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (dma->manager) {
+    *status = HAL_INVALID_DMA_ADDITION;
+    return;
+  }
+
+  int index = 0;
+  auto triggerChannels = dma->captureStore.triggerChannels;
+  do {
+    if (((triggerChannels >> index) & 0x1) == 0) {
+      break;
+    }
+    index++;
+  } while (index < 8);
+
+  if (index == 8) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return;
+  }
+
+  dma->captureStore.triggerChannels |= (1 << index);
+
+  auto channelIndex = index;
+
+  auto isExternalClock = dma->aDMA->readConfig_ExternalClock(status);
+  if (*status == 0 && !isExternalClock) {
+    dma->aDMA->writeConfig_ExternalClock(true, status);
+    if (*status != 0) return;
+  } else if (*status != 0) {
+    return;
+  }
+
+  uint8_t pin = 0;
+  uint8_t module = 0;
+  bool analogTrigger = false;
+  bool success = remapDigitalSource(digitalSourceHandle, analogTriggerType, pin,
+                                    module, analogTrigger);
+
+  if (!success) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+
+  tDMA::tExternalTriggers newTrigger;
+  newTrigger.FallingEdge = falling;
+  newTrigger.RisingEdge = rising;
+  newTrigger.ExternalClockSource_AnalogTrigger = analogTrigger;
+  newTrigger.ExternalClockSource_Channel = pin;
+  newTrigger.ExternalClockSource_Module = module;
+
+  dma->aDMA->writeExternalTriggers(channelIndex / 4, channelIndex % 4,
+                                   newTrigger, status);
+}
+
+void HAL_StartDMA(HAL_DMAHandle handle, int32_t queueDepth, int32_t* status) {
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (dma->manager) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+
+  tDMA::tConfig config = dma->aDMA->readConfig(status);
+  if (*status != 0) return;
+
+  {
+    size_t accum_size = 0;
+#define SET_SIZE(bit)                                      \
+  if (config.bit) {                                        \
+    dma->captureStore.channelOffsets[k##bit] = accum_size; \
+    accum_size += kChannelSize[k##bit];                    \
+  } else {                                                 \
+    dma->captureStore.channelOffsets[k##bit] = -1;         \
+  }
+    SET_SIZE(Enable_AI0_Low);
+    SET_SIZE(Enable_AI0_High);
+    SET_SIZE(Enable_AIAveraged0_Low);
+    SET_SIZE(Enable_AIAveraged0_High);
+    SET_SIZE(Enable_AI1_Low);
+    SET_SIZE(Enable_AI1_High);
+    SET_SIZE(Enable_AIAveraged1_Low);
+    SET_SIZE(Enable_AIAveraged1_High);
+    SET_SIZE(Enable_Accumulator0);
+    SET_SIZE(Enable_Accumulator1);
+    SET_SIZE(Enable_DI);
+    SET_SIZE(Enable_AnalogTriggers);
+    SET_SIZE(Enable_Counters_Low);
+    SET_SIZE(Enable_Counters_High);
+    SET_SIZE(Enable_CounterTimers_Low);
+    SET_SIZE(Enable_CounterTimers_High);
+    SET_SIZE(Enable_Encoders_Low);
+    SET_SIZE(Enable_Encoders_High);
+    SET_SIZE(Enable_EncoderTimers_Low);
+    SET_SIZE(Enable_EncoderTimers_High);
+    SET_SIZE(Enable_DutyCycle_Low);
+    SET_SIZE(Enable_DutyCycle_High);
+#undef SET_SIZE
+    dma->captureStore.captureSize = accum_size + 1;
+  }
+
+  dma->manager = std::make_unique<tDMAManager>(
+      g_DMA_index, queueDepth * dma->captureStore.captureSize, status);
+  if (*status != 0) {
+    return;
+  }
+
+  dma->manager->start(status);
+  dma->manager->stop(status);
+  dma->manager->start(status);
+}
+
+void HAL_StopDMA(HAL_DMAHandle handle, int32_t* status) {
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (dma->manager) {
+    dma->manager->stop(status);
+    dma->manager = nullptr;
+  }
+}
+
+void* HAL_GetDMADirectPointer(HAL_DMAHandle handle) {
+  auto dma = dmaHandles->Get(handle);
+  return dma.get();
+}
+
+enum HAL_DMAReadStatus HAL_ReadDMADirect(void* dmaPointer,
+                                         HAL_DMASample* dmaSample,
+                                         int32_t timeoutMs,
+                                         int32_t* remainingOut,
+                                         int32_t* status) {
+  DMA* dma = static_cast<DMA*>(dmaPointer);
+  *remainingOut = 0;
+  size_t remainingBytes = 0;
+
+  if (!dma->manager) {
+    *status = INCOMPATIBLE_STATE;
+    return HAL_DMA_ERROR;
+  }
+
+  dma->manager->read(dmaSample->readBuffer, dma->captureStore.captureSize,
+                     timeoutMs, &remainingBytes, status);
+
+  *remainingOut = remainingBytes / dma->captureStore.captureSize;
+
+  if (*status == 0) {
+    uint32_t lower_sample =
+        dmaSample->readBuffer[dma->captureStore.captureSize - 1];
+    dmaSample->timeStamp = HAL_ExpandFPGATime(lower_sample, status);
+    if (*status != 0) {
+      return HAL_DMA_ERROR;
+    }
+    dmaSample->triggerChannels = dma->captureStore.triggerChannels;
+    dmaSample->captureSize = dma->captureStore.captureSize;
+    std::memcpy(dmaSample->channelOffsets, dma->captureStore.channelOffsets,
+                sizeof(dmaSample->channelOffsets));
+    return HAL_DMA_OK;
+  } else if (*status == NiFpga_Status_FifoTimeout) {
+    *status = 0;
+    return HAL_DMA_TIMEOUT;
+  } else {
+    return HAL_DMA_ERROR;
+  }
+}
+
+enum HAL_DMAReadStatus HAL_ReadDMA(HAL_DMAHandle handle,
+                                   HAL_DMASample* dmaSample, int32_t timeoutMs,
+                                   int32_t* remainingOut, int32_t* status) {
+  auto dma = dmaHandles->Get(handle);
+  if (!dma) {
+    *status = HAL_HANDLE_ERROR;
+    return HAL_DMA_ERROR;
+  }
+
+  return HAL_ReadDMADirect(dma.get(), dmaSample, timeoutMs, remainingOut,
+                           status);
+}
+
+static uint32_t ReadDMAValue(const HAL_DMASample& dma, int valueType, int index,
+                             int32_t* status) {
+  auto offset = dma.channelOffsets[valueType];
+  if (offset == -1) {
+    *status = NiFpga_Status_ResourceNotFound;
+    return 0;
+  }
+  return dma.readBuffer[offset + index];
+}
+
+uint64_t HAL_GetDMASampleTime(const HAL_DMASample* dmaSample, int32_t* status) {
+  return dmaSample->timeStamp;
+}
+
+int32_t HAL_GetDMASampleEncoderRaw(const HAL_DMASample* dmaSample,
+                                   HAL_EncoderHandle encoderHandle,
+                                   int32_t* status) {
+  HAL_FPGAEncoderHandle fpgaEncoderHandle = 0;
+  HAL_CounterHandle counterHandle = 0;
+  bool validEncoderHandle = hal::GetEncoderBaseHandle(
+      encoderHandle, &fpgaEncoderHandle, &counterHandle);
+
+  if (!validEncoderHandle) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  if (counterHandle != HAL_kInvalidHandle) {
+    return HAL_GetDMASampleCounter(dmaSample, counterHandle, status);
+  }
+
+  if (getHandleType(fpgaEncoderHandle) != HAL_HandleEnum::FPGAEncoder) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  int32_t index = getHandleIndex(fpgaEncoderHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  uint32_t dmaWord = 0;
+  *status = 0;
+  if (index < 4) {
+    dmaWord = ReadDMAValue(*dmaSample, kEnable_Encoders_Low, index, status);
+  } else if (index < 8) {
+    dmaWord =
+        ReadDMAValue(*dmaSample, kEnable_Encoders_High, index - 4, status);
+  } else {
+    *status = NiFpga_Status_ResourceNotFound;
+  }
+  if (*status != 0) {
+    return -1;
+  }
+
+  return static_cast<int32_t>(dmaWord) >> 1;
+}
+
+int32_t HAL_GetDMASampleEncoderPeriodRaw(const HAL_DMASample* dmaSample,
+                                         HAL_EncoderHandle encoderHandle,
+                                         int32_t* status) {
+  HAL_FPGAEncoderHandle fpgaEncoderHandle = 0;
+  HAL_CounterHandle counterHandle = 0;
+  bool validEncoderHandle = hal::GetEncoderBaseHandle(
+      encoderHandle, &fpgaEncoderHandle, &counterHandle);
+
+  if (!validEncoderHandle) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  if (counterHandle != HAL_kInvalidHandle) {
+    return HAL_GetDMASampleCounterPeriod(dmaSample, counterHandle, status);
+  }
+
+  if (getHandleType(fpgaEncoderHandle) != HAL_HandleEnum::FPGAEncoder) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  int32_t index = getHandleIndex(fpgaEncoderHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  uint32_t dmaWord = 0;
+  *status = 0;
+  if (index < 4) {
+    dmaWord =
+        ReadDMAValue(*dmaSample, kEnable_EncoderTimers_Low, index, status);
+  } else if (index < 8) {
+    dmaWord =
+        ReadDMAValue(*dmaSample, kEnable_EncoderTimers_High, index - 4, status);
+  } else {
+    *status = NiFpga_Status_ResourceNotFound;
+  }
+  if (*status != 0) {
+    return -1;
+  }
+
+  return static_cast<int32_t>(dmaWord) & 0x7FFFFF;
+}
+
+int32_t HAL_GetDMASampleCounter(const HAL_DMASample* dmaSample,
+                                HAL_CounterHandle counterHandle,
+                                int32_t* status) {
+  if (getHandleType(counterHandle) != HAL_HandleEnum::Counter) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  int32_t index = getHandleIndex(counterHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  uint32_t dmaWord = 0;
+  *status = 0;
+  if (index < 4) {
+    dmaWord = ReadDMAValue(*dmaSample, kEnable_Counters_Low, index, status);
+  } else if (index < 8) {
+    dmaWord =
+        ReadDMAValue(*dmaSample, kEnable_Counters_High, index - 4, status);
+  } else {
+    *status = NiFpga_Status_ResourceNotFound;
+  }
+  if (*status != 0) {
+    return -1;
+  }
+
+  return static_cast<int32_t>(dmaWord) >> 1;
+}
+
+int32_t HAL_GetDMASampleCounterPeriod(const HAL_DMASample* dmaSample,
+                                      HAL_CounterHandle counterHandle,
+                                      int32_t* status) {
+  if (getHandleType(counterHandle) != HAL_HandleEnum::Counter) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  int32_t index = getHandleIndex(counterHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  uint32_t dmaWord = 0;
+  *status = 0;
+  if (index < 4) {
+    dmaWord =
+        ReadDMAValue(*dmaSample, kEnable_CounterTimers_Low, index, status);
+  } else if (index < 8) {
+    dmaWord =
+        ReadDMAValue(*dmaSample, kEnable_CounterTimers_High, index - 4, status);
+  } else {
+    *status = NiFpga_Status_ResourceNotFound;
+  }
+  if (*status != 0) {
+    return -1;
+  }
+
+  return static_cast<int32_t>(dmaWord) & 0x7FFFFF;
+}
+
+HAL_Bool HAL_GetDMASampleDigitalSource(const HAL_DMASample* dmaSample,
+                                       HAL_Handle dSourceHandle,
+                                       int32_t* status) {
+  HAL_HandleEnum handleType = getHandleType(dSourceHandle);
+  int32_t index = getHandleIndex(dSourceHandle);
+
+  *status = 0;
+  if (handleType == HAL_HandleEnum::DIO) {
+    auto readVal = ReadDMAValue(*dmaSample, kEnable_DI, 0, status);
+    if (*status == 0) {
+      if (index < kNumDigitalHeaders) {
+        return (readVal >> index) & 0x1;
+      } else {
+        return (readVal >> (index + 6)) & 0x1;
+      }
+    }
+  } else if (handleType == HAL_HandleEnum::AnalogTrigger) {
+    auto readVal = ReadDMAValue(*dmaSample, kEnable_AnalogTriggers, 0, status);
+    if (*status == 0) {
+      return (readVal >> index) & 0x1;
+    }
+  } else {
+    *status = NiFpga_Status_InvalidParameter;
+  }
+  return false;
+}
+int32_t HAL_GetDMASampleAnalogInputRaw(const HAL_DMASample* dmaSample,
+                                       HAL_AnalogInputHandle aInHandle,
+                                       int32_t* status) {
+  if (getHandleType(aInHandle) != HAL_HandleEnum::AnalogInput) {
+    *status = HAL_HANDLE_ERROR;
+    return 0xFFFFFFFF;
+  }
+
+  int32_t index = getHandleIndex(aInHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return 0xFFFFFFFF;
+  }
+
+  uint32_t dmaWord = 0;
+  if (index < 4) {
+    dmaWord = ReadDMAValue(*dmaSample, kEnable_AI0_Low, index / 2, status);
+  } else if (index < 8) {
+    dmaWord =
+        ReadDMAValue(*dmaSample, kEnable_AI0_High, (index - 4) / 2, status);
+  } else {
+    *status = NiFpga_Status_ResourceNotFound;
+  }
+  if (*status != 0) {
+    return 0xFFFFFFFF;
+  }
+
+  if (index % 2) {
+    return (dmaWord >> 16) & 0xffff;
+  } else {
+    return dmaWord & 0xffff;
+  }
+}
+
+int32_t HAL_GetDMASampleAveragedAnalogInputRaw(const HAL_DMASample* dmaSample,
+                                               HAL_AnalogInputHandle aInHandle,
+                                               int32_t* status) {
+  if (getHandleType(aInHandle) != HAL_HandleEnum::AnalogInput) {
+    *status = HAL_HANDLE_ERROR;
+    return 0xFFFFFFFF;
+  }
+
+  int32_t index = getHandleIndex(aInHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return 0xFFFFFFFF;
+  }
+
+  uint32_t dmaWord = 0;
+  if (index < 4) {
+    dmaWord = ReadDMAValue(*dmaSample, kEnable_AIAveraged0_Low, index, status);
+  } else if (index < 8) {
+    dmaWord =
+        ReadDMAValue(*dmaSample, kEnable_AIAveraged0_High, index - 4, status);
+  } else {
+    *status = NiFpga_Status_ResourceNotFound;
+  }
+  if (*status != 0) {
+    return 0xFFFFFFFF;
+  }
+
+  return dmaWord;
+}
+
+void HAL_GetDMASampleAnalogAccumulator(const HAL_DMASample* dmaSample,
+                                       HAL_AnalogInputHandle aInHandle,
+                                       int64_t* count, int64_t* value,
+                                       int32_t* status) {
+  if (!HAL_IsAccumulatorChannel(aInHandle, status)) {
+    *status = HAL_INVALID_ACCUMULATOR_CHANNEL;
+    return;
+  }
+
+  int32_t index = getHandleIndex(aInHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  uint32_t dmaWord = 0;
+  uint32_t dmaValue1 = 0;
+  uint32_t dmaValue2 = 0;
+  if (index == 0) {
+    dmaWord = ReadDMAValue(*dmaSample, kEnable_Accumulator0, index, status);
+    dmaValue1 =
+        ReadDMAValue(*dmaSample, kEnable_Accumulator0, index + 1, status);
+    dmaValue2 =
+        ReadDMAValue(*dmaSample, kEnable_Accumulator0, index + 2, status);
+  } else if (index == 1) {
+    dmaWord = ReadDMAValue(*dmaSample, kEnable_Accumulator1, index - 1, status);
+    dmaValue1 = ReadDMAValue(*dmaSample, kEnable_Accumulator0, index, status);
+    dmaValue2 =
+        ReadDMAValue(*dmaSample, kEnable_Accumulator0, index + 1, status);
+  } else {
+    *status = NiFpga_Status_ResourceNotFound;
+  }
+  if (*status != 0) {
+    return;
+  }
+
+  *count = dmaWord;
+
+  *value = static_cast<int64_t>(dmaValue1) << 32 | dmaValue2;
+}
+
+int32_t HAL_GetDMASampleDutyCycleOutputRaw(const HAL_DMASample* dmaSample,
+                                           HAL_DutyCycleHandle dutyCycleHandle,
+                                           int32_t* status) {
+  if (getHandleType(dutyCycleHandle) != HAL_HandleEnum::DutyCycle) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  int32_t index = getHandleIndex(dutyCycleHandle);
+  if (index < 0) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  uint32_t dmaWord = 0;
+  *status = 0;
+  if (index < 4) {
+    dmaWord = ReadDMAValue(*dmaSample, kEnable_DutyCycle_Low, index, status);
+  } else if (index < 8) {
+    dmaWord =
+        ReadDMAValue(*dmaSample, kEnable_DutyCycle_High, index - 4, status);
+  } else {
+    *status = NiFpga_Status_ResourceNotFound;
+  }
+  if (*status != 0) {
+    return -1;
+  }
+  return dmaWord;
+}
+}  // extern "C"
diff --git a/hal/src/main/native/athena/DigitalInternal.cpp b/hal/src/main/native/athena/DigitalInternal.cpp
index 684d35a..205ce3e 100644
--- a/hal/src/main/native/athena/DigitalInternal.cpp
+++ b/hal/src/main/native/athena/DigitalInternal.cpp
@@ -103,9 +103,9 @@
                     (kSystemClockTicksPerMicrosecond * 1e3);
 
   pwmSystem->writeConfig_Period(
-      static_cast<uint16_t>(kDefaultPwmPeriod / loopTime + .5), status);
+      static_cast<uint16_t>(kDefaultPwmPeriod / loopTime + 0.5), status);
   uint16_t minHigh = static_cast<uint16_t>(
-      (kDefaultPwmCenter - kDefaultPwmStepsDown * loopTime) / loopTime + .5);
+      (kDefaultPwmCenter - kDefaultPwmStepsDown * loopTime) / loopTime + 0.5);
   pwmSystem->writeConfig_MinHigh(minHigh, status);
   // Ensure that PWM output values are set to OFF
   for (uint8_t pwmIndex = 0; pwmIndex < kNumPWMChannels; pwmIndex++) {
diff --git a/hal/src/main/native/athena/DigitalInternal.h b/hal/src/main/native/athena/DigitalInternal.h
index b486f48..2cb9b3c 100644
--- a/hal/src/main/native/athena/DigitalInternal.h
+++ b/hal/src/main/native/athena/DigitalInternal.h
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -97,6 +97,20 @@
                         uint8_t& channel, uint8_t& module, bool& analogTrigger);
 
 /**
+ * Remap the Digital Channel to map to the bitfield channel of the FPGA
+ */
+constexpr int32_t remapDigitalChannelToBitfieldChannel(int32_t channel) {
+  // First 10 are headers
+  if (channel < kNumDigitalHeaders) return channel;
+  // 2nd group of 16 are mxp. So if mxp port, add 6, since they start at 10
+  else if (channel < kNumDigitalMXPChannels)
+    return channel + 6;
+  // Assume SPI, so remove MXP channels
+  else
+    return channel - kNumDigitalMXPChannels;
+}
+
+/**
  * Map DIO channel numbers from their physical number (10 to 26) to their
  * position in the bit field.
  */
diff --git a/hal/src/main/native/athena/DutyCycle.cpp b/hal/src/main/native/athena/DutyCycle.cpp
new file mode 100644
index 0000000..1c1a678
--- /dev/null
+++ b/hal/src/main/native/athena/DutyCycle.cpp
@@ -0,0 +1,124 @@
+/*----------------------------------------------------------------------------*/
+/* 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/DutyCycle.h"
+
+#include <memory>
+
+#include "DigitalInternal.h"
+#include "DutyCycleInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/ChipObject.h"
+#include "hal/Errors.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+
+using namespace hal;
+
+namespace hal {
+LimitedHandleResource<HAL_DutyCycleHandle, DutyCycle, kNumDutyCycles,
+                      HAL_HandleEnum::DutyCycle>* dutyCycleHandles;
+namespace init {
+void InitializeDutyCycle() {
+  static LimitedHandleResource<HAL_DutyCycleHandle, DutyCycle, kNumDutyCycles,
+                               HAL_HandleEnum::DutyCycle>
+      dcH;
+  dutyCycleHandles = &dcH;
+}
+}  // namespace init
+}  // namespace hal
+
+static constexpr int32_t kScaleFactor = 4e7 - 1;
+
+extern "C" {
+HAL_DutyCycleHandle HAL_InitializeDutyCycle(HAL_Handle digitalSourceHandle,
+                                            HAL_AnalogTriggerType triggerType,
+                                            int32_t* status) {
+  hal::init::CheckInit();
+
+  bool routingAnalogTrigger = false;
+  uint8_t routingChannel = 0;
+  uint8_t routingModule = 0;
+  bool success =
+      remapDigitalSource(digitalSourceHandle, triggerType, routingChannel,
+                         routingModule, routingAnalogTrigger);
+
+  if (!success) {
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  HAL_DutyCycleHandle handle = dutyCycleHandles->Allocate();
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+
+  auto dutyCycle = dutyCycleHandles->Get(handle);
+  uint32_t index = static_cast<uint32_t>(getHandleIndex(handle));
+  dutyCycle->dutyCycle.reset(tDutyCycle::create(index, status));
+
+  dutyCycle->dutyCycle->writeSource_AnalogTrigger(routingAnalogTrigger, status);
+  dutyCycle->dutyCycle->writeSource_Channel(routingChannel, status);
+  dutyCycle->dutyCycle->writeSource_Module(routingModule, status);
+  dutyCycle->index = index;
+
+  return handle;
+}
+void HAL_FreeDutyCycle(HAL_DutyCycleHandle dutyCycleHandle) {
+  // Just free it, the unique ptr will take care of everything else
+  dutyCycleHandles->Free(dutyCycleHandle);
+}
+
+int32_t HAL_GetDutyCycleFrequency(HAL_DutyCycleHandle dutyCycleHandle,
+                                  int32_t* status) {
+  auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);
+  if (!dutyCycle) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  // TODO Handle Overflow
+  unsigned char overflow = 0;
+  return dutyCycle->dutyCycle->readFrequency(&overflow, status);
+}
+
+double HAL_GetDutyCycleOutput(HAL_DutyCycleHandle dutyCycleHandle,
+                              int32_t* status) {
+  return HAL_GetDutyCycleOutputRaw(dutyCycleHandle, status) /
+         static_cast<double>(kScaleFactor);
+}
+
+int32_t HAL_GetDutyCycleOutputRaw(HAL_DutyCycleHandle dutyCycleHandle,
+                                  int32_t* status) {
+  auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);
+  if (!dutyCycle) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  // TODO Handle Overflow
+  unsigned char overflow = 0;
+  return dutyCycle->dutyCycle->readOutput(&overflow, status);
+}
+
+int32_t HAL_GetDutyCycleOutputScaleFactor(HAL_DutyCycleHandle dutyCycleHandle,
+                                          int32_t* status) {
+  return kScaleFactor;
+}
+
+int32_t HAL_GetDutyCycleFPGAIndex(HAL_DutyCycleHandle dutyCycleHandle,
+                                  int32_t* status) {
+  auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);
+  if (!dutyCycle) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+  return dutyCycle->index;
+}
+}  // extern "C"
diff --git a/hal/src/main/native/athena/DutyCycleInternal.h b/hal/src/main/native/athena/DutyCycleInternal.h
new file mode 100644
index 0000000..33a8ff2
--- /dev/null
+++ b/hal/src/main/native/athena/DutyCycleInternal.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include "hal/ChipObject.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+
+namespace hal {
+struct DutyCycle {
+  std::unique_ptr<tDutyCycle> dutyCycle;
+  int index;
+};
+
+extern LimitedHandleResource<HAL_DutyCycleHandle, DutyCycle, kNumDutyCycles,
+                             HAL_HandleEnum::DutyCycle>* dutyCycleHandles;
+}  // namespace hal
diff --git a/hal/src/main/native/athena/Encoder.cpp b/hal/src/main/native/athena/Encoder.cpp
index bf3a273..be8c203 100644
--- a/hal/src/main/native/athena/Encoder.cpp
+++ b/hal/src/main/native/athena/Encoder.cpp
@@ -35,7 +35,7 @@
         return;
       }
       m_counter = HAL_kInvalidHandle;
-      SetMaxPeriod(.5, status);
+      SetMaxPeriod(0.5, status);
       break;
     }
     case HAL_Encoder_k1X:
@@ -238,6 +238,19 @@
 }  // namespace init
 }  // namespace hal
 
+namespace hal {
+bool GetEncoderBaseHandle(HAL_EncoderHandle handle,
+                          HAL_FPGAEncoderHandle* fpgaHandle,
+                          HAL_CounterHandle* counterHandle) {
+  auto encoder = encoderHandles->Get(handle);
+  if (!handle) return false;
+
+  *fpgaHandle = encoder->m_encoder;
+  *counterHandle = encoder->m_counter;
+  return true;
+}
+}  // namespace hal
+
 extern "C" {
 HAL_EncoderHandle HAL_InitializeEncoder(
     HAL_Handle digitalSourceHandleA, HAL_AnalogTriggerType analogTriggerTypeA,
diff --git a/hal/src/main/native/athena/EncoderInternal.h b/hal/src/main/native/athena/EncoderInternal.h
index 1e7ed4d..bed4ee3 100644
--- a/hal/src/main/native/athena/EncoderInternal.h
+++ b/hal/src/main/native/athena/EncoderInternal.h
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -13,8 +13,16 @@
 
 namespace hal {
 
+bool GetEncoderBaseHandle(HAL_EncoderHandle handle,
+                          HAL_FPGAEncoderHandle* fpgaEncoderHandle,
+                          HAL_CounterHandle* counterHandle);
+
 class Encoder {
  public:
+  friend bool GetEncoderBaseHandle(HAL_EncoderHandle handle,
+                                   HAL_FPGAEncoderHandle* fpgaEncoderHandle,
+                                   HAL_CounterHandle* counterHandle);
+
   Encoder(HAL_Handle digitalSourceHandleA,
           HAL_AnalogTriggerType analogTriggerTypeA,
           HAL_Handle digitalSourceHandleB,
diff --git a/hal/src/main/native/athena/FRCDriverStation.cpp b/hal/src/main/native/athena/FRCDriverStation.cpp
index 23c874f..5b29815 100644
--- a/hal/src/main/native/athena/FRCDriverStation.cpp
+++ b/hal/src/main/native/athena/FRCDriverStation.cpp
@@ -124,7 +124,7 @@
 
 static wpi::mutex* newDSDataAvailableMutex;
 static wpi::condition_variable* newDSDataAvailableCond;
-static int newDSDataAvailableCounter{0};
+static std::atomic_int newDSDataAvailableCounter{0};
 
 namespace hal {
 namespace init {
@@ -338,14 +338,46 @@
   FRC_NetworkCommunication_observeUserProgramTest();
 }
 
-HAL_Bool HAL_IsNewControlData(void) {
+static int& GetThreadLocalLastCount() {
   // There is a rollover error condition here. At Packet# = n * (uintmax), this
   // will return false when instead it should return true. However, this at a
   // 20ms rate occurs once every 2.7 years of DS connected runtime, so not
   // worth the cycles to check.
   thread_local int lastCount{-1};
-  std::lock_guard lock{*newDSDataAvailableMutex};
-  int currentCount = newDSDataAvailableCounter;
+  return lastCount;
+}
+
+void HAL_WaitForCachedControlData(void) {
+  HAL_WaitForCachedControlDataTimeout(0);
+}
+
+HAL_Bool HAL_WaitForCachedControlDataTimeout(double timeout) {
+  int& lastCount = GetThreadLocalLastCount();
+  int currentCount = newDSDataAvailableCounter.load();
+  if (lastCount != currentCount) {
+    lastCount = currentCount;
+    return true;
+  }
+  auto timeoutTime =
+      std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
+
+  std::unique_lock lock{*newDSDataAvailableMutex};
+  while (newDSDataAvailableCounter.load() == currentCount) {
+    if (timeout > 0) {
+      auto timedOut = newDSDataAvailableCond->wait_until(lock, timeoutTime);
+      if (timedOut == std::cv_status::timeout) {
+        return false;
+      }
+    } else {
+      newDSDataAvailableCond->wait(lock);
+    }
+  }
+  return true;
+}
+
+HAL_Bool HAL_IsNewControlData(void) {
+  int& lastCount = GetThreadLocalLastCount();
+  int currentCount = newDSDataAvailableCounter.load();
   if (lastCount == currentCount) return false;
   lastCount = currentCount;
   return true;
@@ -365,9 +397,9 @@
   auto timeoutTime =
       std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
 
+  int currentCount = newDSDataAvailableCounter.load();
   std::unique_lock lock{*newDSDataAvailableMutex};
-  int currentCount = newDSDataAvailableCounter;
-  while (newDSDataAvailableCounter == currentCount) {
+  while (newDSDataAvailableCounter.load() == currentCount) {
     if (timeout > 0) {
       auto timedOut = newDSDataAvailableCond->wait_until(lock, timeoutTime);
       if (timedOut == std::cv_status::timeout) {
@@ -388,7 +420,7 @@
   // to signal our threads
   if (refNum != refNumber) return;
   // Notify all threads
-  newDSDataAvailableCounter++;
+  newDSDataAvailableCounter.fetch_add(1);
   newDSDataAvailableCond->notify_all();
 }
 
diff --git a/hal/src/main/native/athena/HAL.cpp b/hal/src/main/native/athena/HAL.cpp
index a9abde6..91214e5 100644
--- a/hal/src/main/native/athena/HAL.cpp
+++ b/hal/src/main/native/athena/HAL.cpp
@@ -42,6 +42,7 @@
 namespace hal {
 namespace init {
 void InitializeHAL() {
+  InitializeAddressableLED();
   InitializeAccelerometer();
   InitializeAnalogAccumulator();
   InitializeAnalogGyro();
@@ -56,6 +57,8 @@
   InitializeCounter();
   InitializeDigitalInternal();
   InitializeDIO();
+  InitializeDMA();
+  InitializeDutyCycle();
   InitializeEncoder();
   InitializeFPGAEncoder();
   InitializeFRCDriverStation();
@@ -212,6 +215,10 @@
       return ERR_FRCSystem_NetCommNotResponding_MESSAGE;
     case ERR_FRCSystem_NoDSConnection:
       return ERR_FRCSystem_NoDSConnection_MESSAGE;
+    case HAL_CAN_BUFFER_OVERRUN:
+      return HAL_CAN_BUFFER_OVERRUN_MESSAGE;
+    case HAL_LED_CHANNEL_ERROR:
+      return HAL_LED_CHANNEL_ERROR_MESSAGE;
     default:
       return "Unknown error status";
   }
@@ -253,6 +260,28 @@
   return (upper2 << 32) + lower;
 }
 
+uint64_t HAL_ExpandFPGATime(uint32_t unexpanded_lower, int32_t* status) {
+  // Capture the current FPGA time.  This will give us the upper half of the
+  // clock.
+  uint64_t fpga_time = HAL_GetFPGATime(status);
+  if (*status != 0) return 0;
+
+  // Now, we need to detect the case where the lower bits rolled over after we
+  // sampled.  In that case, the upper bits will be 1 bigger than they should
+  // be.
+
+  // Break it into lower and upper portions.
+  uint32_t lower = fpga_time & 0xffffffffull;
+  uint64_t upper = (fpga_time >> 32) & 0xffffffff;
+
+  // The time was sampled *before* the current time, so roll it back.
+  if (lower < unexpanded_lower) {
+    --upper;
+  }
+
+  return (upper << 32) + static_cast<uint64_t>(unexpanded_lower);
+}
+
 HAL_Bool HAL_GetFPGAButton(int32_t* status) {
   if (!global) {
     *status = NiFpga_Status_ResourceNotInitialized;
diff --git a/hal/src/main/native/athena/HALInitializer.h b/hal/src/main/native/athena/HALInitializer.h
index fc38038..acce386 100644
--- a/hal/src/main/native/athena/HALInitializer.h
+++ b/hal/src/main/native/athena/HALInitializer.h
@@ -19,6 +19,7 @@
 }
 
 extern void InitializeAccelerometer();
+extern void InitializeAddressableLED();
 extern void InitializeAnalogAccumulator();
 extern void InitializeAnalogGyro();
 extern void InitializeAnalogInput();
@@ -32,6 +33,8 @@
 extern void InitializeCounter();
 extern void InitializeDigitalInternal();
 extern void InitializeDIO();
+extern void InitializeDMA();
+extern void InitializeDutyCycle();
 extern void InitializeEncoder();
 extern void InitializeFPGAEncoder();
 extern void InitializeFRCDriverStation();
diff --git a/hal/src/main/native/athena/Interrupts.cpp b/hal/src/main/native/athena/Interrupts.cpp
index b0b2071..78d518c 100644
--- a/hal/src/main/native/athena/Interrupts.cpp
+++ b/hal/src/main/native/athena/Interrupts.cpp
@@ -64,12 +64,6 @@
   }
 };
 
-}  // namespace
-
-static void threadedInterruptHandler(uint32_t mask, void* param) {
-  static_cast<InterruptThreadOwner*>(param)->Notify(mask);
-}
-
 struct Interrupt {
   std::unique_ptr<tInterrupt> anInterrupt;
   std::unique_ptr<tInterruptManager> manager;
@@ -77,6 +71,12 @@
   void* param = nullptr;
 };
 
+}  // namespace
+
+static void threadedInterruptHandler(uint32_t mask, void* param) {
+  static_cast<InterruptThreadOwner*>(param)->Notify(mask);
+}
+
 static LimitedHandleResource<HAL_InterruptHandle, Interrupt, kNumInterrupts,
                              HAL_HandleEnum::Interrupt>* interruptHandles;
 
@@ -118,7 +118,11 @@
   if (anInterrupt == nullptr) {
     return nullptr;
   }
-  anInterrupt->manager->disable(status);
+
+  if (anInterrupt->manager->isEnabled(status)) {
+    anInterrupt->manager->disable(status);
+  }
+
   void* param = anInterrupt->param;
   return param;
 }
@@ -152,7 +156,10 @@
     *status = HAL_HANDLE_ERROR;
     return;
   }
-  anInterrupt->manager->enable(status);
+
+  if (!anInterrupt->manager->isEnabled(status)) {
+    anInterrupt->manager->enable(status);
+  }
 }
 
 void HAL_DisableInterrupts(HAL_InterruptHandle interruptHandle,
@@ -162,7 +169,9 @@
     *status = HAL_HANDLE_ERROR;
     return;
   }
-  anInterrupt->manager->disable(status);
+  if (anInterrupt->manager->isEnabled(status)) {
+    anInterrupt->manager->disable(status);
+  }
 }
 
 int64_t HAL_ReadInterruptRisingTimestamp(HAL_InterruptHandle interruptHandle,
diff --git a/hal/src/main/native/athena/Notifier.cpp b/hal/src/main/native/athena/Notifier.cpp
index 662b04e..c30e8d1 100644
--- a/hal/src/main/native/athena/Notifier.cpp
+++ b/hal/src/main/native/athena/Notifier.cpp
@@ -139,6 +139,9 @@
   return handle;
 }
 
+void HAL_SetNotifierName(HAL_NotifierHandle notifierHandle, const char* name,
+                         int32_t* status) {}
+
 void HAL_StopNotifier(HAL_NotifierHandle notifierHandle, int32_t* status) {
   auto notifier = notifierHandles->Get(notifierHandle);
   if (!notifier) return;
diff --git a/hal/src/main/native/athena/PDP.cpp b/hal/src/main/native/athena/PDP.cpp
index f27f5da..f5cf92b 100644
--- a/hal/src/main/native/athena/PDP.cpp
+++ b/hal/src/main/native/athena/PDP.cpp
@@ -175,7 +175,11 @@
   HAL_ReadCANPacketTimeout(handle, Status3, pdpStatus.data, &length,
                            &receivedTimestamp, TimeoutMs, status);
 
-  return pdpStatus.bits.temp * 1.03250836957542 - 67.8564500484966;
+  if (*status != 0) {
+    return 0;
+  } else {
+    return pdpStatus.bits.temp * 1.03250836957542 - 67.8564500484966;
+  }
 }
 
 double HAL_GetPDPVoltage(HAL_PDPHandle handle, int32_t* status) {
@@ -186,7 +190,11 @@
   HAL_ReadCANPacketTimeout(handle, Status3, pdpStatus.data, &length,
                            &receivedTimestamp, TimeoutMs, status);
 
-  return pdpStatus.bits.busVoltage * 0.05 + 4.0; /* 50mV per unit plus 4V. */
+  if (*status != 0) {
+    return 0;
+  } else {
+    return pdpStatus.bits.busVoltage * 0.05 + 4.0; /* 50mV per unit plus 4V. */
+  }
 }
 
 double HAL_GetPDPChannelCurrent(HAL_PDPHandle handle, int32_t channel,
@@ -205,6 +213,9 @@
     PdpStatus1 pdpStatus;
     HAL_ReadCANPacketTimeout(handle, Status1, pdpStatus.data, &length,
                              &receivedTimestamp, TimeoutMs, status);
+    if (*status != 0) {
+      return 0;
+    }
     switch (channel) {
       case 0:
         raw = (static_cast<uint32_t>(pdpStatus.bits.chan1_h8) << 2) |
@@ -235,6 +246,9 @@
     PdpStatus2 pdpStatus;
     HAL_ReadCANPacketTimeout(handle, Status2, pdpStatus.data, &length,
                              &receivedTimestamp, TimeoutMs, status);
+    if (*status != 0) {
+      return 0;
+    }
     switch (channel) {
       case 6:
         raw = (static_cast<uint32_t>(pdpStatus.bits.chan7_h8) << 2) |
@@ -265,6 +279,9 @@
     PdpStatus3 pdpStatus;
     HAL_ReadCANPacketTimeout(handle, Status3, pdpStatus.data, &length,
                              &receivedTimestamp, TimeoutMs, status);
+    if (*status != 0) {
+      return 0;
+    }
     switch (channel) {
       case 12:
         raw = (static_cast<uint32_t>(pdpStatus.bits.chan13_h8) << 2) |
@@ -289,6 +306,75 @@
   return raw * 0.125; /* 7.3 fixed pt value in Amps */
 }
 
+void HAL_GetPDPAllChannelCurrents(HAL_PDPHandle handle, double* currents,
+                                  int32_t* status) {
+  int32_t length = 0;
+  uint64_t receivedTimestamp = 0;
+  PdpStatus1 pdpStatus;
+  HAL_ReadCANPacketTimeout(handle, Status1, pdpStatus.data, &length,
+                           &receivedTimestamp, TimeoutMs, status);
+  if (*status != 0) return;
+  PdpStatus2 pdpStatus2;
+  HAL_ReadCANPacketTimeout(handle, Status2, pdpStatus2.data, &length,
+                           &receivedTimestamp, TimeoutMs, status);
+  if (*status != 0) return;
+  PdpStatus3 pdpStatus3;
+  HAL_ReadCANPacketTimeout(handle, Status3, pdpStatus3.data, &length,
+                           &receivedTimestamp, TimeoutMs, status);
+  if (*status != 0) return;
+
+  currents[0] = ((static_cast<uint32_t>(pdpStatus.bits.chan1_h8) << 2) |
+                 pdpStatus.bits.chan1_l2) *
+                0.125;
+  currents[1] = ((static_cast<uint32_t>(pdpStatus.bits.chan2_h6) << 4) |
+                 pdpStatus.bits.chan2_l4) *
+                0.125;
+  currents[2] = ((static_cast<uint32_t>(pdpStatus.bits.chan3_h4) << 6) |
+                 pdpStatus.bits.chan3_l6) *
+                0.125;
+  currents[3] = ((static_cast<uint32_t>(pdpStatus.bits.chan4_h2) << 8) |
+                 pdpStatus.bits.chan4_l8) *
+                0.125;
+  currents[4] = ((static_cast<uint32_t>(pdpStatus.bits.chan5_h8) << 2) |
+                 pdpStatus.bits.chan5_l2) *
+                0.125;
+  currents[5] = ((static_cast<uint32_t>(pdpStatus.bits.chan6_h6) << 4) |
+                 pdpStatus.bits.chan6_l4) *
+                0.125;
+
+  currents[6] = ((static_cast<uint32_t>(pdpStatus2.bits.chan7_h8) << 2) |
+                 pdpStatus2.bits.chan7_l2) *
+                0.125;
+  currents[7] = ((static_cast<uint32_t>(pdpStatus2.bits.chan8_h6) << 4) |
+                 pdpStatus2.bits.chan8_l4) *
+                0.125;
+  currents[8] = ((static_cast<uint32_t>(pdpStatus2.bits.chan9_h4) << 6) |
+                 pdpStatus2.bits.chan9_l6) *
+                0.125;
+  currents[9] = ((static_cast<uint32_t>(pdpStatus2.bits.chan10_h2) << 8) |
+                 pdpStatus2.bits.chan10_l8) *
+                0.125;
+  currents[10] = ((static_cast<uint32_t>(pdpStatus2.bits.chan11_h8) << 2) |
+                  pdpStatus2.bits.chan11_l2) *
+                 0.125;
+  currents[11] = ((static_cast<uint32_t>(pdpStatus2.bits.chan12_h6) << 4) |
+                  pdpStatus2.bits.chan12_l4) *
+                 0.125;
+
+  currents[12] = ((static_cast<uint32_t>(pdpStatus3.bits.chan13_h8) << 2) |
+                  pdpStatus3.bits.chan13_l2) *
+                 0.125;
+  currents[13] = ((static_cast<uint32_t>(pdpStatus3.bits.chan14_h6) << 4) |
+                  pdpStatus3.bits.chan14_l4) *
+                 0.125;
+  currents[14] = ((static_cast<uint32_t>(pdpStatus3.bits.chan15_h4) << 6) |
+                  pdpStatus3.bits.chan15_l6) *
+                 0.125;
+  currents[15] = ((static_cast<uint32_t>(pdpStatus3.bits.chan16_h2) << 8) |
+                  pdpStatus3.bits.chan16_l8) *
+                 0.125;
+}
+
 double HAL_GetPDPTotalCurrent(HAL_PDPHandle handle, int32_t* status) {
   PdpStatusEnergy pdpStatus;
   int32_t length = 0;
@@ -296,6 +382,9 @@
 
   HAL_ReadCANPacketTimeout(handle, StatusEnergy, pdpStatus.data, &length,
                            &receivedTimestamp, TimeoutMs, status);
+  if (*status != 0) {
+    return 0;
+  }
 
   uint32_t raw;
   raw = pdpStatus.bits.TotalCurrent_125mAperunit_h8;
@@ -311,6 +400,9 @@
 
   HAL_ReadCANPacketTimeout(handle, StatusEnergy, pdpStatus.data, &length,
                            &receivedTimestamp, TimeoutMs, status);
+  if (*status != 0) {
+    return 0;
+  }
 
   uint32_t raw;
   raw = pdpStatus.bits.Power_125mWperunit_h4;
@@ -328,6 +420,9 @@
 
   HAL_ReadCANPacketTimeout(handle, StatusEnergy, pdpStatus.data, &length,
                            &receivedTimestamp, TimeoutMs, status);
+  if (*status != 0) {
+    return 0;
+  }
 
   uint32_t raw;
   raw = pdpStatus.bits.Energy_125mWPerUnitXTmeas_h4;
diff --git a/hal/src/main/native/athena/Ports.cpp b/hal/src/main/native/athena/Ports.cpp
index 9a52736..47bd400 100644
--- a/hal/src/main/native/athena/Ports.cpp
+++ b/hal/src/main/native/athena/Ports.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -37,5 +37,7 @@
 int32_t HAL_GetNumSolenoidChannels(void) { return kNumSolenoidChannels; }
 int32_t HAL_GetNumPDPModules(void) { return kNumPDPModules; }
 int32_t HAL_GetNumPDPChannels(void) { return kNumPDPChannels; }
+int32_t HAL_GetNumDutyCycles(void) { return kNumDutyCycles; }
+int32_t HAL_GetNumAddressableLEDs(void) { return kNumAddressableLEDs; }
 
 }  // extern "C"
diff --git a/hal/src/main/native/athena/PortsInternal.h b/hal/src/main/native/athena/PortsInternal.h
index b3eb6b0..98fc690 100644
--- a/hal/src/main/native/athena/PortsInternal.h
+++ b/hal/src/main/native/athena/PortsInternal.h
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -35,5 +35,7 @@
 constexpr int32_t kNumSolenoidChannels = 8;
 constexpr int32_t kNumPDPModules = 63;
 constexpr int32_t kNumPDPChannels = 16;
+constexpr int32_t kNumDutyCycles = tDutyCycle::kNumSystems;
+constexpr int32_t kNumAddressableLEDs = tLED::kNumSystems;
 
 }  // namespace hal
diff --git a/hal/src/main/native/athena/SPI.cpp b/hal/src/main/native/athena/SPI.cpp
index bb0666a..80cbf09 100644
--- a/hal/src/main/native/athena/SPI.cpp
+++ b/hal/src/main/native/athena/SPI.cpp
@@ -565,7 +565,7 @@
 void HAL_SetSPIAutoTransmitData(HAL_SPIPort port, const uint8_t* dataToSend,
                                 int32_t dataSize, int32_t zeroSize,
                                 int32_t* status) {
-  if (dataSize < 0 || dataSize > 16) {
+  if (dataSize < 0 || dataSize > 32) {
     *status = PARAMETER_OUT_OF_RANGE;
     return;
   }
@@ -589,7 +589,7 @@
   // set byte counts
   tSPI::tAutoByteCount config;
   config.ZeroByteCount = static_cast<unsigned>(zeroSize) & 0x7f;
-  config.TxByteCount = static_cast<unsigned>(dataSize) & 0xf;
+  config.TxByteCount = static_cast<unsigned>(dataSize) & 0x1f;
   spiSystem->writeAutoByteCount(config, status);
 }
 
@@ -631,4 +631,12 @@
   return spiSystem->readTransferSkippedFullCount(status);
 }
 
+// These 2 functions are so the new stall functionality
+// can be tested. How they're used is not very clear
+// but I want them to be testable so we can add an impl.
+// We will not be including these in the headers
+void* HAL_GetSPIDMAManager() { return spiAutoDMA.get(); }
+
+void* HAL_GetSPISystem() { return spiSystem.get(); }
+
 }  // 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/AnalogJNI.cpp b/hal/src/main/native/cpp/jni/AnalogJNI.cpp
index abd614f..5571d55 100644
--- a/hal/src/main/native/cpp/jni/AnalogJNI.cpp
+++ b/hal/src/main/native/cpp/jni/AnalogJNI.cpp
@@ -486,18 +486,31 @@
 /*
  * Class:     edu_wpi_first_hal_AnalogJNI
  * Method:    initializeAnalogTrigger
- * Signature: (ILjava/lang/Object;)I
+ * Signature: (I)I
  */
 JNIEXPORT jint JNICALL
 Java_edu_wpi_first_hal_AnalogJNI_initializeAnalogTrigger
-  (JNIEnv* env, jclass, jint id, jobject index)
+  (JNIEnv* env, jclass, jint id)
 {
-  jint* indexHandle =
-      reinterpret_cast<jint*>(env->GetDirectBufferAddress(index));
   int32_t status = 0;
-  HAL_AnalogTriggerHandle analogTrigger = HAL_InitializeAnalogTrigger(
-      (HAL_AnalogInputHandle)id, reinterpret_cast<int32_t*>(indexHandle),
-      &status);
+  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;
 }
@@ -533,6 +546,21 @@
 
 /*
  * 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
  */
@@ -622,4 +650,20 @@
   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/DigitalGlitchFilterJNI.cpp b/hal/src/main/native/cpp/jni/DigitalGlitchFilterJNI.cpp
index 3e39ac0..fbbaadb 100644
--- a/hal/src/main/native/cpp/jni/DigitalGlitchFilterJNI.cpp
+++ b/hal/src/main/native/cpp/jni/DigitalGlitchFilterJNI.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -13,6 +13,8 @@
 
 using namespace frc;
 
+extern "C" {
+
 /*
  * Class:     edu_wpi_first_hal_DigitalGlitchFilterJNI
  * Method:    setFilterSelect
@@ -76,3 +78,5 @@
   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/NotifierJNI.cpp b/hal/src/main/native/cpp/jni/NotifierJNI.cpp
index 588614e..874d750 100644
--- a/hal/src/main/native/cpp/jni/NotifierJNI.cpp
+++ b/hal/src/main/native/cpp/jni/NotifierJNI.cpp
@@ -10,6 +10,8 @@
 #include <cassert>
 #include <cstdio>
 
+#include <wpi/jni_util.h>
+
 #include "HALUtil.h"
 #include "edu_wpi_first_hal_NotifierJNI.h"
 #include "hal/Notifier.h"
@@ -39,6 +41,21 @@
 
 /*
  * 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
  */
diff --git a/hal/src/main/native/cpp/jni/PDPJNI.cpp b/hal/src/main/native/cpp/jni/PDPJNI.cpp
index e8173be..f649a8d 100644
--- a/hal/src/main/native/cpp/jni/PDPJNI.cpp
+++ b/hal/src/main/native/cpp/jni/PDPJNI.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -100,6 +100,25 @@
 
 /*
  * 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
  */
diff --git a/hal/src/main/native/include/hal/AddressableLED.h b/hal/src/main/native/include/hal/AddressableLED.h
new file mode 100644
index 0000000..68383ef
--- /dev/null
+++ b/hal/src/main/native/include/hal/AddressableLED.h
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/AddressableLEDTypes.h"
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_addressable Addressable LED Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+HAL_AddressableLEDHandle HAL_InitializeAddressableLED(
+    HAL_DigitalHandle outputPort, int32_t* status);
+
+void HAL_FreeAddressableLED(HAL_AddressableLEDHandle handle);
+
+void HAL_SetAddressableLEDOutputPort(HAL_AddressableLEDHandle handle,
+                                     HAL_DigitalHandle outputPort,
+                                     int32_t* status);
+
+void HAL_SetAddressableLEDLength(HAL_AddressableLEDHandle handle,
+                                 int32_t length, int32_t* status);
+
+void HAL_WriteAddressableLEDData(HAL_AddressableLEDHandle handle,
+                                 const struct HAL_AddressableLEDData* data,
+                                 int32_t length, int32_t* status);
+
+void HAL_SetAddressableLEDBitTiming(HAL_AddressableLEDHandle handle,
+                                    int32_t lowTime0NanoSeconds,
+                                    int32_t highTime0NanoSeconds,
+                                    int32_t lowTime1NanoSeconds,
+                                    int32_t highTime1NanoSeconds,
+                                    int32_t* status);
+
+void HAL_SetAddressableLEDSyncTime(HAL_AddressableLEDHandle handle,
+                                   int32_t syncTimeMicroSeconds,
+                                   int32_t* status);
+
+void HAL_StartAddressableLEDOutput(HAL_AddressableLEDHandle handle,
+                                   int32_t* status);
+
+void HAL_StopAddressableLEDOutput(HAL_AddressableLEDHandle handle,
+                                  int32_t* status);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/hal/src/main/native/include/hal/AddressableLEDTypes.h b/hal/src/main/native/include/hal/AddressableLEDTypes.h
new file mode 100644
index 0000000..bdcd742
--- /dev/null
+++ b/hal/src/main/native/include/hal/AddressableLEDTypes.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#define HAL_kAddressableLEDMaxLength 5460
+
+struct HAL_AddressableLEDData {
+  uint8_t b;
+  uint8_t g;
+  uint8_t r;
+  uint8_t padding;
+};
diff --git a/hal/src/main/native/include/hal/AnalogInput.h b/hal/src/main/native/include/hal/AnalogInput.h
index c0e45b3..95ba4e0 100644
--- a/hal/src/main/native/include/hal/AnalogInput.h
+++ b/hal/src/main/native/include/hal/AnalogInput.h
@@ -233,6 +233,16 @@
  */
 int32_t HAL_GetAnalogOffset(HAL_AnalogInputHandle analogPortHandle,
                             int32_t* status);
+
+/**
+ *  Get the analog voltage from a raw value.
+ *
+ * @param analogPortHandle  Handle to the analog port the values were read from.
+ * @param rawValue          The raw analog value
+ * @return                  The voltage relating to the value
+ */
+double HAL_GetAnalogValueToVolts(HAL_AnalogInputHandle analogPortHandle,
+                                 int32_t rawValue, int32_t* status);
 #ifdef __cplusplus
 }  // extern "C"
 #endif
diff --git a/hal/src/main/native/include/hal/AnalogTrigger.h b/hal/src/main/native/include/hal/AnalogTrigger.h
index f461f1d..85d7680 100644
--- a/hal/src/main/native/include/hal/AnalogTrigger.h
+++ b/hal/src/main/native/include/hal/AnalogTrigger.h
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -37,11 +37,17 @@
  * Initializes an analog trigger.
  *
  * @param portHandle the analog input to use for triggering
- * @param index      the trigger index value (output)
  * @return           the created analog trigger handle
  */
 HAL_AnalogTriggerHandle HAL_InitializeAnalogTrigger(
-    HAL_AnalogInputHandle portHandle, int32_t* index, int32_t* status);
+    HAL_AnalogInputHandle portHandle, int32_t* status);
+
+/**
+ * Initializes an analog trigger with a Duty Cycle input
+ *
+ */
+HAL_AnalogTriggerHandle HAL_InitializeAnalogTriggerDutyCycle(
+    HAL_DutyCycleHandle dutyCycleHandle, int32_t* status);
 
 /**
  * Frees an analog trigger.
@@ -54,7 +60,8 @@
 /**
  * Sets the raw ADC upper and lower limits of the analog trigger.
  *
- * HAL_SetAnalogTriggerLimitsVoltage is likely better in most cases.
+ * HAL_SetAnalogTriggerLimitsVoltage or HAL_SetAnalogTriggerLimitsDutyCycle
+ * is likely better in most cases.
  *
  * @param analogTriggerHandle the trigger handle
  * @param lower               the lower ADC value
@@ -77,12 +84,19 @@
     HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper,
     int32_t* status);
 
+void HAL_SetAnalogTriggerLimitsDutyCycle(
+    HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper,
+    int32_t* status);
+
 /**
  * Configures the analog trigger to use the averaged vs. raw values.
  *
  * If the value is true, then the averaged value is selected for the analog
  * trigger, otherwise the immediate value is used.
  *
+ * This is not allowed to be used if filtered mode is set.
+ * This is not allowed to be used with Duty Cycle based inputs.
+ *
  * @param analogTriggerHandle the trigger handle
  * @param useAveragedValue    true to use averaged values, false for raw
  */
@@ -96,6 +110,8 @@
  * is designed to help with 360 degree pot applications for the period where the
  * pot crosses through zero.
  *
+ * This is not allowed to be used if averaged mode is set.
+ *
  * @param analogTriggerHandle the trigger handle
  * @param useFilteredValue    true to use filtered values, false for average or
  * raw
@@ -137,6 +153,15 @@
 HAL_Bool HAL_GetAnalogTriggerOutput(HAL_AnalogTriggerHandle analogTriggerHandle,
                                     HAL_AnalogTriggerType type,
                                     int32_t* status);
+
+/**
+ * Get the FPGA index for the AnlogTrigger.
+ *
+ * @param analogTriggerHandle the trigger handle
+ * @return the FPGA index
+ */
+int32_t HAL_GetAnalogTriggerFPGAIndex(
+    HAL_AnalogTriggerHandle analogTriggerHandle, int32_t* status);
 #ifdef __cplusplus
 }  // extern "C"
 #endif
diff --git a/hal/src/main/native/include/hal/CANAPITypes.h b/hal/src/main/native/include/hal/CANAPITypes.h
index 31a64ab..a23cee1 100644
--- a/hal/src/main/native/include/hal/CANAPITypes.h
+++ b/hal/src/main/native/include/hal/CANAPITypes.h
@@ -55,7 +55,8 @@
   HAL_CAN_Man_kTeamUse = 8,
   HAL_CAN_Man_kKauaiLabs = 9,
   HAL_CAN_Man_kCopperforge = 10,
-  HAL_CAN_Man_kPWF = 11
+  HAL_CAN_Man_kPWF = 11,
+  HAL_CAN_Man_kStudica = 12
 };
 // clang-format on
 /** @} */
diff --git a/hal/src/main/native/include/hal/ChipObject.h b/hal/src/main/native/include/hal/ChipObject.h
index 878595b..9b321c2 100644
--- a/hal/src/main/native/include/hal/ChipObject.h
+++ b/hal/src/main/native/include/hal/ChipObject.h
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2008-2018 FIRST. All Rights Reserved.                        */
+/* Copyright (c) 2008-2019 FIRST. All Rights Reserved.                        */
 /* Open Source Software - may be modified and shared by FRC teams. The code   */
 /* must be accompanied by the FIRST BSD license file in the root directory of */
 /* the project.                                                               */
@@ -24,9 +24,11 @@
 #include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tCounter.h>
 #include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDIO.h>
 #include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDMA.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDutyCycle.h>
 #include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tEncoder.h>
 #include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tGlobal.h>
 #include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tInterrupt.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tLED.h>
 #include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPWM.h>
 #include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPower.h>
 #include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tRelay.h>
diff --git a/hal/src/main/native/include/hal/DMA.h b/hal/src/main/native/include/hal/DMA.h
new file mode 100644
index 0000000..38aaca2
--- /dev/null
+++ b/hal/src/main/native/include/hal/DMA.h
@@ -0,0 +1,129 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/AnalogTrigger.h"
+#include "hal/Types.h"
+
+// clang-format off
+/**
+ * The DMA Read Status.
+ */
+HAL_ENUM(HAL_DMAReadStatus ) {
+  HAL_DMA_OK = 1,
+  HAL_DMA_TIMEOUT = 2,
+  HAL_DMA_ERROR = 3,
+};
+// clang-format on
+
+struct HAL_DMASample {
+  uint32_t readBuffer[74];
+  int32_t channelOffsets[22];
+  uint64_t timeStamp;
+  uint32_t captureSize;
+  uint8_t triggerChannels;
+};
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+HAL_DMAHandle HAL_InitializeDMA(int32_t* status);
+void HAL_FreeDMA(HAL_DMAHandle handle);
+
+void HAL_SetDMAPause(HAL_DMAHandle handle, HAL_Bool pause, int32_t* status);
+void HAL_SetDMARate(HAL_DMAHandle handle, int32_t cycles, int32_t* status);
+
+void HAL_AddDMAEncoder(HAL_DMAHandle handle, HAL_EncoderHandle encoderHandle,
+                       int32_t* status);
+void HAL_AddDMAEncoderPeriod(HAL_DMAHandle handle,
+                             HAL_EncoderHandle encoderHandle, int32_t* status);
+void HAL_AddDMACounter(HAL_DMAHandle handle, HAL_CounterHandle counterHandle,
+                       int32_t* status);
+void HAL_AddDMACounterPeriod(HAL_DMAHandle handle,
+                             HAL_CounterHandle counterHandle, int32_t* status);
+void HAL_AddDMADigitalSource(HAL_DMAHandle handle,
+                             HAL_Handle digitalSourceHandle, int32_t* status);
+void HAL_AddDMAAnalogInput(HAL_DMAHandle handle,
+                           HAL_AnalogInputHandle aInHandle, int32_t* status);
+
+void HAL_AddDMAAveragedAnalogInput(HAL_DMAHandle handle,
+                                   HAL_AnalogInputHandle aInHandle,
+                                   int32_t* status);
+
+void HAL_AddDMAAnalogAccumulator(HAL_DMAHandle handle,
+                                 HAL_AnalogInputHandle aInHandle,
+                                 int32_t* status);
+
+void HAL_AddDMADutyCycle(HAL_DMAHandle handle,
+                         HAL_DutyCycleHandle dutyCycleHandle, int32_t* status);
+
+void HAL_SetDMAExternalTrigger(HAL_DMAHandle handle,
+                               HAL_Handle digitalSourceHandle,
+                               HAL_AnalogTriggerType analogTriggerType,
+                               HAL_Bool rising, HAL_Bool falling,
+                               int32_t* status);
+
+void HAL_StartDMA(HAL_DMAHandle handle, int32_t queueDepth, int32_t* status);
+void HAL_StopDMA(HAL_DMAHandle handle, int32_t* status);
+
+void* HAL_GetDMADirectPointer(HAL_DMAHandle handle);
+
+enum HAL_DMAReadStatus HAL_ReadDMADirect(void* dmaPointer,
+                                         HAL_DMASample* dmaSample,
+                                         int32_t timeoutMs,
+                                         int32_t* remainingOut,
+                                         int32_t* status);
+
+enum HAL_DMAReadStatus HAL_ReadDMA(HAL_DMAHandle handle,
+                                   HAL_DMASample* dmaSample, int32_t timeoutMs,
+                                   int32_t* remainingOut, int32_t* status);
+
+// Sampling Code
+uint64_t HAL_GetDMASampleTime(const HAL_DMASample* dmaSample, int32_t* status);
+
+int32_t HAL_GetDMASampleEncoderRaw(const HAL_DMASample* dmaSample,
+                                   HAL_EncoderHandle encoderHandle,
+                                   int32_t* status);
+
+int32_t HAL_GetDMASampleCounter(const HAL_DMASample* dmaSample,
+                                HAL_CounterHandle counterHandle,
+                                int32_t* status);
+
+int32_t HAL_GetDMASampleEncoderPeriodRaw(const HAL_DMASample* dmaSample,
+                                         HAL_EncoderHandle encoderHandle,
+                                         int32_t* status);
+
+int32_t HAL_GetDMASampleCounterPeriod(const HAL_DMASample* dmaSample,
+                                      HAL_CounterHandle counterHandle,
+                                      int32_t* status);
+HAL_Bool HAL_GetDMASampleDigitalSource(const HAL_DMASample* dmaSample,
+                                       HAL_Handle dSourceHandle,
+                                       int32_t* status);
+int32_t HAL_GetDMASampleAnalogInputRaw(const HAL_DMASample* dmaSample,
+                                       HAL_AnalogInputHandle aInHandle,
+                                       int32_t* status);
+
+int32_t HAL_GetDMASampleAveragedAnalogInputRaw(const HAL_DMASample* dmaSample,
+                                               HAL_AnalogInputHandle aInHandle,
+                                               int32_t* status);
+
+void HAL_GetDMASampleAnalogAccumulator(const HAL_DMASample* dmaSample,
+                                       HAL_AnalogInputHandle aInHandle,
+                                       int64_t* count, int64_t* value,
+                                       int32_t* status);
+
+int32_t HAL_GetDMASampleDutyCycleOutputRaw(const HAL_DMASample* dmaSample,
+                                           HAL_DutyCycleHandle dutyCycleHandle,
+                                           int32_t* status);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
diff --git a/hal/src/main/native/include/hal/DriverStation.h b/hal/src/main/native/include/hal/DriverStation.h
index db98698..471c18b 100644
--- a/hal/src/main/native/include/hal/DriverStation.h
+++ b/hal/src/main/native/include/hal/DriverStation.h
@@ -194,6 +194,24 @@
 void HAL_ReleaseDSMutex(void);
 
 /**
+ * Checks if new control data has arrived since the last
+ * HAL_WaitForCachedControlData or HAL_IsNewControlData call. If new data has
+ * not arrived, waits for new data to arrive. Otherwise, returns immediately.
+ */
+void HAL_WaitForCachedControlData(void);
+
+/**
+ * Checks if new control data has arrived since the last
+ * HAL_WaitForCachedControlData or HAL_IsNewControlData call. If new data has
+ * not arrived, waits for new data to arrive, or a timeout. Otherwise, returns
+ * immediately.
+ *
+ * @param timeout timeout in seconds
+ * @return        true for new data, false for timeout
+ */
+HAL_Bool HAL_WaitForCachedControlDataTimeout(double timeout);
+
+/**
  * Has a new control packet from the driver station arrived since the last
  * time this function was called?
  *
diff --git a/hal/src/main/native/include/hal/DutyCycle.h b/hal/src/main/native/include/hal/DutyCycle.h
new file mode 100644
index 0000000..357d8f3
--- /dev/null
+++ b/hal/src/main/native/include/hal/DutyCycle.h
@@ -0,0 +1,109 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "hal/AnalogTrigger.h"
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_dutycycle DutyCycle Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initialize a DutyCycle input.
+ *
+ * @param digitalSourceHandle the digital source to use (either a
+ * HAL_DigitalHandle or a HAL_AnalogTriggerHandle)
+ * @param triggerType the analog trigger type of the source if it is
+ * an analog trigger
+ * @return thre created duty cycle handle
+ */
+HAL_DutyCycleHandle HAL_InitializeDutyCycle(HAL_Handle digitalSourceHandle,
+                                            HAL_AnalogTriggerType triggerType,
+                                            int32_t* status);
+
+/**
+ * Free a DutyCycle.
+ *
+ * @param dutyCycleHandle the duty cycle handle
+ */
+void HAL_FreeDutyCycle(HAL_DutyCycleHandle dutyCycleHandle);
+
+/**
+ * Indicates the duty cycle is used by a simulated device.
+ *
+ * @param handle the duty cycle handle
+ * @param device simulated device handle
+ */
+void HAL_SetDutyCycleSimDevice(HAL_DutyCycleHandle handle,
+                               HAL_SimDeviceHandle device);
+
+/**
+ * Get the frequency of the duty cycle signal.
+ *
+ * @param dutyCycleHandle the duty cycle handle
+ * @return frequency in Hertz
+ */
+int32_t HAL_GetDutyCycleFrequency(HAL_DutyCycleHandle dutyCycleHandle,
+                                  int32_t* status);
+
+/**
+ * Get the output ratio of the duty cycle signal.
+ *
+ * <p> 0 means always low, 1 means always high.
+ *
+ * @param dutyCycleHandle the duty cycle handle
+ * @return output ratio between 0 and 1
+ */
+double HAL_GetDutyCycleOutput(HAL_DutyCycleHandle dutyCycleHandle,
+                              int32_t* status);
+
+/**
+ * Get the raw output ratio of the duty cycle signal.
+ *
+ * <p> 0 means always low, an output equal to
+ * GetOutputScaleFactor() means always high.
+ *
+ * @param dutyCycleHandle the duty cycle handle
+ * @return output ratio in raw units
+ */
+int32_t HAL_GetDutyCycleOutputRaw(HAL_DutyCycleHandle dutyCycleHandle,
+                                  int32_t* status);
+
+/**
+ * Get the scale factor of the output.
+ *
+ * <p> An output equal to this value is always high, and then linearly scales
+ * down to 0. Divide the result of getOutputRaw by this in order to get the
+ * percentage between 0 and 1.
+ *
+ * @param dutyCycleHandle the duty cycle handle
+ * @return the output scale factor
+ */
+int32_t HAL_GetDutyCycleOutputScaleFactor(HAL_DutyCycleHandle dutyCycleHandle,
+                                          int32_t* status);
+
+/**
+ * Get the FPGA index for the DutyCycle.
+ *
+ * @param dutyCycleHandle the duty cycle handle
+ * @return the FPGA index
+ */
+int32_t HAL_GetDutyCycleFPGAIndex(HAL_DutyCycleHandle dutyCycleHandle,
+                                  int32_t* status);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/hal/src/main/native/include/hal/Errors.h b/hal/src/main/native/include/hal/Errors.h
index 4476ab0..9f74f8c 100644
--- a/hal/src/main/native/include/hal/Errors.h
+++ b/hal/src/main/native/include/hal/Errors.h
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -94,6 +94,14 @@
 #define HAL_HANDLE_ERROR_MESSAGE \
   "HAL: A handle parameter was passed incorrectly"
 
+#define HAL_LED_CHANNEL_ERROR -1099
+#define HAL_LED_CHANNEL_ERROR_MESSAGE \
+  "HAL: Addressable LEDs only supported on PWM Headers, not MXP or DIO"
+
+#define HAL_INVALID_DMA_ADDITION -1102
+#define HAL_INVALID_DMA_ADDITION_MESSAGE \
+  "HAL_AddDMA() only works before HAL_StartDMA()"
+
 #define HAL_SERIAL_PORT_NOT_FOUND -1123
 #define HAL_SERIAL_PORT_NOT_FOUND_MESSAGE \
   "HAL: The specified serial port device was not found"
@@ -117,6 +125,13 @@
 #define HAL_CAN_TIMEOUT -1154
 #define HAL_CAN_TIMEOUT_MESSAGE "HAL: CAN Receive has Timed Out"
 
+#define HAL_SIM_NOT_SUPPORTED -1155
+#define HAL_SIM_NOT_SUPPORTED_MESSAGE "HAL: Method not supported in sim"
+
+#define HAL_CAN_BUFFER_OVERRUN -35007
+#define HAL_CAN_BUFFER_OVERRUN_MESSAGE \
+  "HAL: CAN Output Buffer Full. Ensure a device is attached"
+
 #define VI_ERROR_SYSTEM_ERROR_MESSAGE "HAL - VISA: System Error";
 #define VI_ERROR_INV_OBJECT_MESSAGE "HAL - VISA: Invalid Object"
 #define VI_ERROR_RSRC_LOCKED_MESSAGE "HAL - VISA: Resource Locked"
diff --git a/hal/src/main/native/include/hal/Extensions.h b/hal/src/main/native/include/hal/Extensions.h
index 0fcbcba..3a435c0 100644
--- a/hal/src/main/native/include/hal/Extensions.h
+++ b/hal/src/main/native/include/hal/Extensions.h
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -7,6 +7,8 @@
 
 #pragma once
 
+#include "hal/Types.h"
+
 /**
  * @defgroup hal_extensions Simulator Extensions
  * @ingroup hal_capi
@@ -41,5 +43,19 @@
  * @return        the succes state of the initialization
  */
 int HAL_LoadExtensions(void);
+
+/**
+ * Enables or disables the message saying no HAL extensions were found.
+ *
+ * Some apps don't care, and the message create clutter. For general team code,
+ * we want it.
+ *
+ * This must be called before HAL_Initialize is called.
+ *
+ * This defaults to true.
+ *
+ * @param showMessage true to show message, false to not.
+ */
+void HAL_SetShowExtensionsNotFoundMessages(HAL_Bool showMessage);
 }  // extern "C"
 /** @} */
diff --git a/hal/src/main/native/include/hal/HAL.h b/hal/src/main/native/include/hal/HAL.h
index 2f71d79..4412886 100644
--- a/hal/src/main/native/include/hal/HAL.h
+++ b/hal/src/main/native/include/hal/HAL.h
@@ -24,6 +24,7 @@
 #include "hal/DriverStation.h"
 #include "hal/Encoder.h"
 #include "hal/Errors.h"
+#include "hal/FRCUsageReporting.h"
 #include "hal/HALBase.h"
 #include "hal/I2C.h"
 #include "hal/Interrupts.h"
@@ -41,7 +42,3 @@
 #include "hal/Threads.h"
 #include "hal/Types.h"
 #include "hal/Value.h"
-
-#ifdef __cplusplus
-#include "hal/FRCUsageReporting.h"
-#endif
diff --git a/hal/src/main/native/include/hal/HALBase.h b/hal/src/main/native/include/hal/HALBase.h
index a958f2b..f61d9e4 100644
--- a/hal/src/main/native/include/hal/HALBase.h
+++ b/hal/src/main/native/include/hal/HALBase.h
@@ -110,6 +110,20 @@
 uint64_t HAL_GetFPGATime(int32_t* status);
 
 /**
+ * Given an 32 bit FPGA time, expand it to the nearest likely 64 bit FPGA time.
+ *
+ * Note: This is making the assumption that the timestamp being converted is
+ * always in the past.  If you call this with a future timestamp, it probably
+ * will make it in the past.  If you wait over 70 minutes between capturing the
+ * bottom 32 bits of the timestamp and expanding it, you will be off by
+ * multiples of 1<<32 microseconds.
+ *
+ * @return The current time in microseconds according to the FPGA (since FPGA
+ * reset) as a 64 bit number.
+ */
+uint64_t HAL_ExpandFPGATime(uint32_t unexpanded_lower, int32_t* status);
+
+/**
  * Call this to start up HAL. This is required for robot programs.
  *
  * This must be called before any other HAL functions. Failure to do so will
@@ -135,34 +149,6 @@
  */
 HAL_Bool HAL_Initialize(int32_t timeout, int32_t mode);
 
-// ifdef's definition is to allow for default parameters in C++.
-#ifdef __cplusplus
-/**
- * Reports a hardware usage to the HAL.
- *
- * @param resource       the used resource
- * @param instanceNumber the instance of the resource
- * @param context        a user specified context index
- * @param feature        a user specified feature string
- * @return               the index of the added value in NetComm
- */
-int64_t HAL_Report(int32_t resource, int32_t instanceNumber,
-                   int32_t context = 0, const char* feature = nullptr);
-#else
-
-/**
- * Reports a hardware usage to the HAL.
- *
- * @param resource       the used resource
- * @param instanceNumber the instance of the resource
- * @param context        a user specified context index
- * @param feature        a user specified feature string
- * @return               the index of the added value in NetComm
- */
-int64_t HAL_Report(int32_t resource, int32_t instanceNumber, int32_t context,
-                   const char* feature);
-#endif
-
 #ifdef __cplusplus
 }  // extern "C"
 #endif
diff --git a/hal/src/main/native/include/hal/Notifier.h b/hal/src/main/native/include/hal/Notifier.h
index 27f20e3..6b8e39f 100644
--- a/hal/src/main/native/include/hal/Notifier.h
+++ b/hal/src/main/native/include/hal/Notifier.h
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -32,6 +32,15 @@
 HAL_NotifierHandle HAL_InitializeNotifier(int32_t* status);
 
 /**
+ * Sets the name of a notifier.
+ *
+ * @param notifierHandle the notifier handle
+ * @param name name
+ */
+void HAL_SetNotifierName(HAL_NotifierHandle notifierHandle, const char* name,
+                         int32_t* status);
+
+/**
  * Stops a notifier from running.
  *
  * This will cause any call into HAL_WaitForNotifierAlarm to return.
diff --git a/hal/src/main/native/include/hal/PDP.h b/hal/src/main/native/include/hal/PDP.h
index 50873f8..c80e8b6 100644
--- a/hal/src/main/native/include/hal/PDP.h
+++ b/hal/src/main/native/include/hal/PDP.h
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -80,6 +80,17 @@
                                 int32_t* status);
 
 /**
+ * Gets the current of all 16 channels on the PDP.
+ *
+ * The array must be large enough to hold all channels.
+ *
+ * @param handle the module handle
+ * @param current the currents (output)
+ */
+void HAL_GetPDPAllChannelCurrents(HAL_PDPHandle handle, double* currents,
+                                  int32_t* status);
+
+/**
  * Gets the total current of the PDP.
  *
  * @param handle the module handle
diff --git a/hal/src/main/native/include/hal/Ports.h b/hal/src/main/native/include/hal/Ports.h
index 9b29817..584bc4f 100644
--- a/hal/src/main/native/include/hal/Ports.h
+++ b/hal/src/main/native/include/hal/Ports.h
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -144,6 +144,20 @@
  * @return the number of PDP channels
  */
 int32_t HAL_GetNumPDPChannels(void);
+
+/**
+ * Gets the number of duty cycle inputs in the current system.
+ *
+ * @return the number of Duty Cycle inputs
+ */
+int32_t HAL_GetNumDutyCycles(void);
+
+/**
+ * Gets the number of addressable LED generators in the current system.
+ *
+ * @return the number of Addressable LED generators
+ */
+int32_t HAL_GetNumAddressableLEDs(void);
 #ifdef __cplusplus
 }  // extern "C"
 #endif
diff --git a/hal/src/main/native/include/hal/Types.h b/hal/src/main/native/include/hal/Types.h
index 5ce6009..1ebbe2d 100644
--- a/hal/src/main/native/include/hal/Types.h
+++ b/hal/src/main/native/include/hal/Types.h
@@ -57,6 +57,12 @@
 
 typedef HAL_Handle HAL_SimValueHandle;
 
+typedef HAL_Handle HAL_DMAHandle;
+
+typedef HAL_Handle HAL_DutyCycleHandle;
+
+typedef HAL_Handle HAL_AddressableLEDHandle;
+
 typedef HAL_CANHandle HAL_PDPHandle;
 
 typedef int32_t HAL_Bool;
diff --git a/hal/src/main/native/include/hal/handles/HandlesInternal.h b/hal/src/main/native/include/hal/handles/HandlesInternal.h
index 5340d82..511433e 100644
--- a/hal/src/main/native/include/hal/handles/HandlesInternal.h
+++ b/hal/src/main/native/include/hal/handles/HandlesInternal.h
@@ -66,6 +66,9 @@
   SimulationJni = 18,
   CAN = 19,
   SerialPort = 20,
+  DutyCycle = 21,
+  DMA = 22,
+  AddressableLED = 23,
 };
 
 /**
diff --git a/hal/src/main/native/include/mockdata/AddressableLEDData.h b/hal/src/main/native/include/mockdata/AddressableLEDData.h
new file mode 100644
index 0000000..0d8f3f3
--- /dev/null
+++ b/hal/src/main/native/include/mockdata/AddressableLEDData.h
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "NotifyListener.h"
+#include "hal/AddressableLEDTypes.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetAddressableLEDData(int32_t index);
+
+int32_t HALSIM_RegisterAddressableLEDInitializedCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelAddressableLEDInitializedCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetAddressableLEDInitialized(int32_t index);
+void HALSIM_SetAddressableLEDInitialized(int32_t index, HAL_Bool initialized);
+
+int32_t HALSIM_RegisterAddressableLEDOutputPortCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelAddressableLEDOutputPortCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetAddressableLEDOutputPort(int32_t index);
+void HALSIM_SetAddressableLEDOutputPort(int32_t index, int32_t outputPort);
+
+int32_t HALSIM_RegisterAddressableLEDLengthCallback(int32_t index,
+                                                    HAL_NotifyCallback callback,
+                                                    void* param,
+                                                    HAL_Bool initialNotify);
+void HALSIM_CancelAddressableLEDLengthCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetAddressableLEDLength(int32_t index);
+void HALSIM_SetAddressableLEDLength(int32_t index, int32_t length);
+
+int32_t HALSIM_RegisterAddressableLEDRunningCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelAddressableLEDRunningCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetAddressableLEDRunning(int32_t index);
+void HALSIM_SetAddressableLEDRunning(int32_t index, HAL_Bool running);
+
+int32_t HALSIM_RegisterAddressableLEDDataCallback(
+    int32_t index, HAL_ConstBufferCallback callback, void* param);
+void HALSIM_CancelAddressableLEDDataCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetAddressableLEDData(int32_t index,
+                                     struct HAL_AddressableLEDData* data);
+void HALSIM_SetAddressableLEDData(int32_t index,
+                                  const struct HAL_AddressableLEDData* data,
+                                  int32_t length);
+
+void HALSIM_RegisterAddressableLEDAllCallbacks(int32_t index,
+                                               HAL_NotifyCallback callback,
+                                               void* param,
+                                               HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
diff --git a/hal/src/main/native/include/mockdata/AnalogTriggerData.h b/hal/src/main/native/include/mockdata/AnalogTriggerData.h
index 7f06c2e..566f2f5 100644
--- a/hal/src/main/native/include/mockdata/AnalogTriggerData.h
+++ b/hal/src/main/native/include/mockdata/AnalogTriggerData.h
@@ -13,6 +13,7 @@
 enum HALSIM_AnalogTriggerMode : int32_t {
   HALSIM_AnalogTriggerUnassigned,
   HALSIM_AnalogTriggerFiltered,
+  HALSIM_AnalogTriggerDutyCycle,
   HALSIM_AnalogTriggerAveraged
 };
 
diff --git a/hal/src/main/native/include/mockdata/DutyCycleData.h b/hal/src/main/native/include/mockdata/DutyCycleData.h
new file mode 100644
index 0000000..b97b355
--- /dev/null
+++ b/hal/src/main/native/include/mockdata/DutyCycleData.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetDutyCycleData(int32_t index);
+int32_t HALSIM_GetDutyCycleDigitalChannel(int32_t index);
+
+int32_t HALSIM_RegisterDutyCycleInitializedCallback(int32_t index,
+                                                    HAL_NotifyCallback callback,
+                                                    void* param,
+                                                    HAL_Bool initialNotify);
+void HALSIM_CancelDutyCycleInitializedCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetDutyCycleInitialized(int32_t index);
+void HALSIM_SetDutyCycleInitialized(int32_t index, HAL_Bool initialized);
+
+HAL_SimDeviceHandle HALSIM_GetDutyCycleSimDevice(int32_t index);
+
+int32_t HALSIM_RegisterDutyCycleOutputCallback(int32_t index,
+                                               HAL_NotifyCallback callback,
+                                               void* param,
+                                               HAL_Bool initialNotify);
+void HALSIM_CancelDutyCycleOutputCallback(int32_t index, int32_t uid);
+double HALSIM_GetDutyCycleOutput(int32_t index);
+void HALSIM_SetDutyCycleOutput(int32_t index, double output);
+
+int32_t HALSIM_RegisterDutyCycleFrequencyCallback(int32_t index,
+                                                  HAL_NotifyCallback callback,
+                                                  void* param,
+                                                  HAL_Bool initialNotify);
+void HALSIM_CancelDutyCycleFrequencyCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetDutyCycleFrequency(int32_t index);
+void HALSIM_SetDutyCycleFrequency(int32_t index, int32_t frequency);
+
+void HALSIM_RegisterDutyCycleAllCallbacks(int32_t index,
+                                          HAL_NotifyCallback callback,
+                                          void* param, HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
diff --git a/hal/src/main/native/include/mockdata/MockHooks.h b/hal/src/main/native/include/mockdata/MockHooks.h
index 02401b0..318ff21 100644
--- a/hal/src/main/native/include/mockdata/MockHooks.h
+++ b/hal/src/main/native/include/mockdata/MockHooks.h
@@ -14,6 +14,10 @@
 void HALSIM_SetProgramStarted(void);
 HAL_Bool HALSIM_GetProgramStarted(void);
 void HALSIM_RestartTiming(void);
+void HALSIM_PauseTiming(void);
+void HALSIM_ResumeTiming(void);
+HAL_Bool HALSIM_IsTimingPaused(void);
+void HALSIM_StepTiming(uint64_t delta);
 
 typedef int32_t (*HALSIM_SendErrorHandler)(
     HAL_Bool isError, int32_t errorCode, HAL_Bool isLVCode, const char* details,
diff --git a/hal/src/main/native/include/mockdata/NotifierData.h b/hal/src/main/native/include/mockdata/NotifierData.h
new file mode 100644
index 0000000..b1ed50f
--- /dev/null
+++ b/hal/src/main/native/include/mockdata/NotifierData.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+struct HALSIM_NotifierInfo {
+  HAL_NotifierHandle handle;
+  char name[64];
+  uint64_t timeout;
+  HAL_Bool running;
+};
+
+uint64_t HALSIM_GetNextNotifierTimeout(void);
+
+int32_t HALSIM_GetNumNotifiers(void);
+
+/**
+ * Gets detailed information about each notifier.
+ *
+ * @param arr array of information to be filled
+ * @param size size of arr
+ * @return Number of notifiers; note: may be larger than passed-in size
+ */
+int32_t HALSIM_GetNotifierInfo(struct HALSIM_NotifierInfo* arr, int32_t size);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
diff --git a/hal/src/main/native/include/mockdata/PCMData.h b/hal/src/main/native/include/mockdata/PCMData.h
index 74a591a..66b1ec2 100644
--- a/hal/src/main/native/include/mockdata/PCMData.h
+++ b/hal/src/main/native/include/mockdata/PCMData.h
@@ -74,6 +74,9 @@
 double HALSIM_GetPCMCompressorCurrent(int32_t index);
 void HALSIM_SetPCMCompressorCurrent(int32_t index, double compressorCurrent);
 
+void HALSIM_GetPCMAllSolenoids(int32_t index, uint8_t* values);
+void HALSIM_SetPCMAllSolenoids(int32_t index, uint8_t values);
+
 void HALSIM_RegisterPCMAllNonSolenoidCallbacks(int32_t index,
                                                HAL_NotifyCallback callback,
                                                void* param,
diff --git a/hal/src/main/native/include/mockdata/PDPData.h b/hal/src/main/native/include/mockdata/PDPData.h
index a25b66d..8315e3c 100644
--- a/hal/src/main/native/include/mockdata/PDPData.h
+++ b/hal/src/main/native/include/mockdata/PDPData.h
@@ -46,6 +46,9 @@
 double HALSIM_GetPDPCurrent(int32_t index, int32_t channel);
 void HALSIM_SetPDPCurrent(int32_t index, int32_t channel, double current);
 
+void HALSIM_GetPDPAllCurrents(int32_t index, double* currents);
+void HALSIM_SetPDPAllCurrents(int32_t index, const double* currents);
+
 void HALSIM_RegisterPDPAllNonCurrentCallbacks(int32_t index, int32_t channel,
                                               HAL_NotifyCallback callback,
                                               void* param,
diff --git a/hal/src/main/native/include/simulation/DutyCycleSim.h b/hal/src/main/native/include/simulation/DutyCycleSim.h
new file mode 100644
index 0000000..f55dfc9
--- /dev/null
+++ b/hal/src/main/native/include/simulation/DutyCycleSim.h
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/DutyCycleData.h"
+
+namespace frc {
+namespace sim {
+class DutyCycleSim {
+ public:
+  explicit DutyCycleSim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterInitializedCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelDutyCycleInitializedCallback);
+    store->SetUid(HALSIM_RegisterDutyCycleInitializedCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetInitialized() const {
+    return HALSIM_GetDutyCycleInitialized(m_index);
+  }
+
+  void SetInitialized(bool initialized) {
+    HALSIM_SetDutyCycleInitialized(m_index, initialized);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterFrequencyCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelDutyCycleFrequencyCallback);
+    store->SetUid(HALSIM_RegisterDutyCycleFrequencyCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetFrequency() const { return HALSIM_GetDutyCycleFrequency(m_index); }
+
+  void SetFrequency(int count) { HALSIM_SetDutyCycleFrequency(m_index, count); }
+
+  std::unique_ptr<CallbackStore> RegisterOutputCallback(NotifyCallback callback,
+                                                        bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelDutyCycleOutputCallback);
+    store->SetUid(HALSIM_RegisterDutyCycleOutputCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetOutput() const { return HALSIM_GetDutyCycleOutput(m_index); }
+
+  void SetOutput(double period) { HALSIM_SetDutyCycleOutput(m_index, period); }
+
+  void ResetData() { HALSIM_ResetDutyCycleData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
diff --git a/hal/src/main/native/include/simulation/PCMSim.h b/hal/src/main/native/include/simulation/PCMSim.h
index 3f3ca9b..b6fcd5a 100644
--- a/hal/src/main/native/include/simulation/PCMSim.h
+++ b/hal/src/main/native/include/simulation/PCMSim.h
@@ -138,6 +138,16 @@
     HALSIM_SetPCMCompressorCurrent(m_index, compressorCurrent);
   }
 
+  uint8_t GetAllSolenoidOutputs() {
+    uint8_t ret = 0;
+    HALSIM_GetPCMAllSolenoids(m_index, &ret);
+    return ret;
+  }
+
+  void SetAllSolenoidOutputs(uint8_t outputs) {
+    HALSIM_SetPCMAllSolenoids(m_index, outputs);
+  }
+
   void ResetData() { HALSIM_ResetPCMData(m_index); }
 
  private:
diff --git a/hal/src/main/native/include/simulation/PDPSim.h b/hal/src/main/native/include/simulation/PDPSim.h
index e3ffd4b..72d8233 100644
--- a/hal/src/main/native/include/simulation/PDPSim.h
+++ b/hal/src/main/native/include/simulation/PDPSim.h
@@ -79,6 +79,14 @@
     HALSIM_SetPDPCurrent(m_index, channel, current);
   }
 
+  void GetAllCurrents(double* currents) {
+    HALSIM_GetPDPAllCurrents(m_index, currents);
+  }
+
+  void SetAllCurrents(const double* currents) {
+    HALSIM_SetPDPAllCurrents(m_index, currents);
+  }
+
   void ResetData() { HALSIM_ResetPDPData(m_index); }
 
  private:
diff --git a/hal/src/main/native/include/simulation/SimDeviceSim.h b/hal/src/main/native/include/simulation/SimDeviceSim.h
new file mode 100644
index 0000000..5705a08
--- /dev/null
+++ b/hal/src/main/native/include/simulation/SimDeviceSim.h
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+#include <memory>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include "CallbackStore.h"
+#include "hal/SimDevice.h"
+#include "mockdata/SimDeviceData.h"
+
+namespace frc {
+namespace sim {
+class SimDeviceSim {
+ public:
+  explicit SimDeviceSim(const char* name)
+      : m_handle{HALSIM_GetSimDeviceHandle(name)} {}
+
+  hal::SimValue GetValue(const char* name) const {
+    return HALSIM_GetSimValueHandle(m_handle, name);
+  }
+
+  hal::SimDouble GetDouble(const char* name) const {
+    return HALSIM_GetSimValueHandle(m_handle, name);
+  }
+
+  hal::SimEnum GetEnum(const char* name) const {
+    return HALSIM_GetSimValueHandle(m_handle, name);
+  }
+
+  hal::SimBoolean GetBoolean(const char* name) const {
+    return HALSIM_GetSimValueHandle(m_handle, name);
+  }
+
+  static std::vector<std::string> GetEnumOptions(hal::SimEnum val) {
+    int32_t numOptions;
+    const char** options = HALSIM_GetSimValueEnumOptions(val, &numOptions);
+    std::vector<std::string> rv;
+    rv.reserve(numOptions);
+    for (int32_t i = 0; i < numOptions; ++i) rv.emplace_back(options[i]);
+    return rv;
+  }
+
+  template <typename F>
+  void EnumerateValues(F callback) const {
+    return HALSIM_EnumerateSimValues(
+        m_handle, &callback,
+        [](const char* name, void* param, HAL_SimValueHandle handle,
+           HAL_Bool readonly, const struct HAL_Value* value) {
+          std::invoke(*static_cast<F*>(param), name, handle, readonly, value);
+        });
+  }
+
+  operator HAL_SimDeviceHandle() const { return m_handle; }
+
+  template <typename F>
+  static void EnumerateDevices(const char* prefix, F callback) {
+    return HALSIM_EnumerateSimDevices(
+        prefix, &callback,
+        [](const char* name, void* param, HAL_SimDeviceHandle handle) {
+          std::invoke(*static_cast<F*>(param), name, handle);
+        });
+  }
+
+  static void ResetData() { HALSIM_ResetSimDeviceData(); }
+
+ private:
+  HAL_SimDeviceHandle m_handle;
+};
+}  // namespace sim
+}  // namespace frc
diff --git a/hal/src/main/native/sim/AddressableLED.cpp b/hal/src/main/native/sim/AddressableLED.cpp
new file mode 100644
index 0000000..70d3f6f
--- /dev/null
+++ b/hal/src/main/native/sim/AddressableLED.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 "hal/AddressableLED.h"
+
+#include "DigitalInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/Errors.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+#include "mockdata/AddressableLEDDataInternal.h"
+
+using namespace hal;
+
+namespace {
+struct AddressableLED {
+  uint8_t index;
+};
+}  // namespace
+
+static LimitedHandleResource<HAL_AddressableLEDHandle, AddressableLED,
+                             kNumAddressableLEDs,
+                             HAL_HandleEnum::AddressableLED>* ledHandles;
+
+namespace hal {
+namespace init {
+void InitializeAddressableLED() {
+  static LimitedHandleResource<HAL_AddressableLEDHandle, AddressableLED,
+                               kNumAddressableLEDs,
+                               HAL_HandleEnum::AddressableLED>
+      dcH;
+  ledHandles = &dcH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+HAL_AddressableLEDHandle HAL_InitializeAddressableLED(
+    HAL_DigitalHandle outputPort, int32_t* status) {
+  hal::init::CheckInit();
+
+  auto digitalPort =
+      hal::digitalChannelHandles->Get(outputPort, hal::HAL_HandleEnum::PWM);
+
+  if (!digitalPort) {
+    // If DIO was passed, channel error, else generic error
+    if (getHandleType(outputPort) == hal::HAL_HandleEnum::DIO) {
+      *status = HAL_LED_CHANNEL_ERROR;
+    } else {
+      *status = HAL_HANDLE_ERROR;
+    }
+    return HAL_kInvalidHandle;
+  }
+
+  if (digitalPort->channel >= kNumPWMHeaders) {
+    *status = HAL_LED_CHANNEL_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  HAL_AddressableLEDHandle handle = ledHandles->Allocate();
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+
+  auto led = ledHandles->Get(handle);
+  if (!led) {  // would only occur on thread issue
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  int16_t index = getHandleIndex(handle);
+  SimAddressableLEDData[index].outputPort = digitalPort->channel;
+  SimAddressableLEDData[index].length = 1;
+  SimAddressableLEDData[index].running = false;
+  SimAddressableLEDData[index].initialized = true;
+  led->index = index;
+  return handle;
+}
+
+void HAL_FreeAddressableLED(HAL_AddressableLEDHandle handle) {
+  auto led = ledHandles->Get(handle);
+  ledHandles->Free(handle);
+  if (!led) return;
+  SimAddressableLEDData[led->index].running = false;
+  SimAddressableLEDData[led->index].initialized = false;
+}
+
+void HAL_SetAddressableLEDOutputPort(HAL_AddressableLEDHandle handle,
+                                     HAL_DigitalHandle outputPort,
+                                     int32_t* status) {
+  auto led = ledHandles->Get(handle);
+  if (!led) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (auto port = digitalChannelHandles->Get(outputPort, HAL_HandleEnum::PWM)) {
+    SimAddressableLEDData[led->index].outputPort = port->channel;
+  } else {
+    SimAddressableLEDData[led->index].outputPort = -1;
+  }
+}
+
+void HAL_SetAddressableLEDLength(HAL_AddressableLEDHandle handle,
+                                 int32_t length, int32_t* status) {
+  auto led = ledHandles->Get(handle);
+  if (!led) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (length > HAL_kAddressableLEDMaxLength) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+  SimAddressableLEDData[led->index].length = length;
+}
+
+void HAL_WriteAddressableLEDData(HAL_AddressableLEDHandle handle,
+                                 const struct HAL_AddressableLEDData* data,
+                                 int32_t length, int32_t* status) {
+  auto led = ledHandles->Get(handle);
+  if (!led) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (length > SimAddressableLEDData[led->index].length) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+  SimAddressableLEDData[led->index].SetData(data, length);
+}
+
+void HAL_SetAddressableLEDBitTiming(HAL_AddressableLEDHandle handle,
+                                    int32_t lowTime0NanoSeconds,
+                                    int32_t highTime0NanoSeconds,
+                                    int32_t lowTime1NanoSeconds,
+                                    int32_t highTime1NanoSeconds,
+                                    int32_t* status) {}
+
+void HAL_SetAddressableLEDSyncTime(HAL_AddressableLEDHandle handle,
+                                   int32_t syncTimeMicroSeconds,
+                                   int32_t* status) {}
+
+void HAL_StartAddressableLEDOutput(HAL_AddressableLEDHandle handle,
+                                   int32_t* status) {
+  auto led = ledHandles->Get(handle);
+  if (!led) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  SimAddressableLEDData[led->index].running = true;
+}
+
+void HAL_StopAddressableLEDOutput(HAL_AddressableLEDHandle handle,
+                                  int32_t* status) {
+  auto led = ledHandles->Get(handle);
+  if (!led) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  SimAddressableLEDData[led->index].running = false;
+}
+}  // extern "C"
diff --git a/hal/src/main/native/sim/AnalogInput.cpp b/hal/src/main/native/sim/AnalogInput.cpp
index dc56403..8ecde74 100644
--- a/hal/src/main/native/sim/AnalogInput.cpp
+++ b/hal/src/main/native/sim/AnalogInput.cpp
@@ -165,6 +165,15 @@
 
   return SimAnalogInData[port->channel].voltage;
 }
+
+double HAL_GetAnalogValueToVolts(HAL_AnalogInputHandle analogPortHandle,
+                                 int32_t rawValue, int32_t* status) {
+  int32_t LSBWeight = HAL_GetAnalogLSBWeight(analogPortHandle, status);
+  int32_t offset = HAL_GetAnalogOffset(analogPortHandle, status);
+  double voltage = LSBWeight * 1.0e-9 * rawValue - offset * 1.0e-9;
+  return voltage;
+}
+
 double HAL_GetAnalogAverageVoltage(HAL_AnalogInputHandle analogPortHandle,
                                    int32_t* status) {
   auto port = analogInputHandles->Get(analogPortHandle);
diff --git a/hal/src/main/native/sim/AnalogTrigger.cpp b/hal/src/main/native/sim/AnalogTrigger.cpp
index 53b165c..3ddacee 100644
--- a/hal/src/main/native/sim/AnalogTrigger.cpp
+++ b/hal/src/main/native/sim/AnalogTrigger.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -63,7 +63,7 @@
 extern "C" {
 
 HAL_AnalogTriggerHandle HAL_InitializeAnalogTrigger(
-    HAL_AnalogInputHandle portHandle, int32_t* index, int32_t* status) {
+    HAL_AnalogInputHandle portHandle, int32_t* status) {
   hal::init::CheckInit();
   // ensure we are given a valid and active AnalogInput handle
   auto analog_port = analogInputHandles->Get(portHandle);
@@ -83,7 +83,6 @@
   }
   trigger->analogHandle = portHandle;
   trigger->index = static_cast<uint8_t>(getHandleIndex(handle));
-  *index = trigger->index;
 
   SimAnalogTriggerData[trigger->index].initialized = true;
 
@@ -92,6 +91,12 @@
   return handle;
 }
 
+HAL_AnalogTriggerHandle HAL_InitializeAnalogTriggerDutyCycle(
+    HAL_DutyCycleHandle dutyCycleHandle, int32_t* status) {
+  *status = HAL_SIM_NOT_SUPPORTED;
+  return HAL_kInvalidHandle;
+}
+
 void HAL_CleanAnalogTrigger(HAL_AnalogTriggerHandle analogTriggerHandle,
                             int32_t* status) {
   auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
@@ -133,6 +138,13 @@
   SimAnalogTriggerData[trigger->index].triggerUpperBound = trigUpper;
   SimAnalogTriggerData[trigger->index].triggerLowerBound = trigLower;
 }
+
+void HAL_SetAnalogTriggerLimitsDutyCycle(
+    HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper,
+    int32_t* status) {
+  *status = HAL_SIM_NOT_SUPPORTED;
+}
+
 void HAL_SetAnalogTriggerLimitsVoltage(
     HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper,
     int32_t* status) {
@@ -158,7 +170,7 @@
 
   AnalogTriggerData* triggerData = &SimAnalogTriggerData[trigger->index];
 
-  if (triggerData->triggerMode.Get() == HALSIM_AnalogTriggerFiltered) {
+  if (triggerData->triggerMode.Get() != HALSIM_AnalogTriggerUnassigned) {
     *status = INCOMPATIBLE_STATE;
     return;
   }
@@ -167,6 +179,7 @@
                                  : HALSIM_AnalogTriggerUnassigned;
   triggerData->triggerMode = setVal;
 }
+
 void HAL_SetAnalogTriggerFiltered(HAL_AnalogTriggerHandle analogTriggerHandle,
                                   HAL_Bool useFilteredValue, int32_t* status) {
   auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
@@ -177,12 +190,12 @@
 
   AnalogTriggerData* triggerData = &SimAnalogTriggerData[trigger->index];
 
-  if (triggerData->triggerMode.Get() == HALSIM_AnalogTriggerAveraged) {
+  if (triggerData->triggerMode.Get() != HALSIM_AnalogTriggerUnassigned) {
     *status = INCOMPATIBLE_STATE;
     return;
   }
 
-  auto setVal = useFilteredValue ? HALSIM_AnalogTriggerAveraged
+  auto setVal = useFilteredValue ? HALSIM_AnalogTriggerFiltered
                                  : HALSIM_AnalogTriggerUnassigned;
   triggerData->triggerMode = setVal;
 }
@@ -258,4 +271,15 @@
     return false;
   }
 }
+
+int32_t HAL_GetAnalogTriggerFPGAIndex(
+    HAL_AnalogTriggerHandle analogTriggerHandle, int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+  return trigger->index;
+}
+
 }  // extern "C"
diff --git a/hal/src/main/native/sim/CAN.cpp b/hal/src/main/native/sim/CAN.cpp
index d55eafd..1e7af73 100644
--- a/hal/src/main/native/sim/CAN.cpp
+++ b/hal/src/main/native/sim/CAN.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -26,8 +26,16 @@
 void HAL_CAN_ReceiveMessage(uint32_t* messageID, uint32_t messageIDMask,
                             uint8_t* data, uint8_t* dataSize,
                             uint32_t* timeStamp, int32_t* status) {
+  // Use a data size of 42 as call check. Difficult to add check to invoke
+  // handler
+  *dataSize = 42;
+  auto tmpStatus = *status;
   SimCanData->receiveMessage(messageID, messageIDMask, data, dataSize,
                              timeStamp, status);
+  // If no handler invoked, return message not found
+  if (*dataSize == 42 && *status == tmpStatus) {
+    *status = HAL_ERR_CANSessionMux_MessageNotFound;
+  }
 }
 void HAL_CAN_OpenStreamSession(uint32_t* sessionHandle, uint32_t messageID,
                                uint32_t messageIDMask, uint32_t maxMessages,
diff --git a/hal/src/main/native/sim/DMA.cpp b/hal/src/main/native/sim/DMA.cpp
new file mode 100644
index 0000000..cea5a29
--- /dev/null
+++ b/hal/src/main/native/sim/DMA.cpp
@@ -0,0 +1,124 @@
+/*----------------------------------------------------------------------------*/
+/* 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/DMA.h"
+
+extern "C" {
+HAL_DMAHandle HAL_InitializeDMA(int32_t* status) { return HAL_kInvalidHandle; }
+void HAL_FreeDMA(HAL_DMAHandle handle) {}
+
+void HAL_SetDMAPause(HAL_DMAHandle handle, HAL_Bool pause, int32_t* status) {}
+void HAL_SetDMARate(HAL_DMAHandle handle, int32_t cycles, int32_t* status) {}
+
+void HAL_AddDMAEncoder(HAL_DMAHandle handle, HAL_EncoderHandle encoderHandle,
+                       int32_t* status) {}
+void HAL_AddDMAEncoderPeriod(HAL_DMAHandle handle,
+                             HAL_EncoderHandle encoderHandle, int32_t* status) {
+}
+void HAL_AddDMACounter(HAL_DMAHandle handle, HAL_CounterHandle counterHandle,
+                       int32_t* status) {}
+void HAL_AddDMACounterPeriod(HAL_DMAHandle handle,
+                             HAL_CounterHandle counterHandle, int32_t* status) {
+}
+void HAL_AddDMADigitalSource(HAL_DMAHandle handle,
+                             HAL_Handle digitalSourceHandle, int32_t* status) {}
+void HAL_AddDMAAnalogInput(HAL_DMAHandle handle,
+                           HAL_AnalogInputHandle aInHandle, int32_t* status) {}
+
+void HAL_AddDMAAveragedAnalogInput(HAL_DMAHandle handle,
+                                   HAL_AnalogInputHandle aInHandle,
+                                   int32_t* status) {}
+
+void HAL_AddDMAAnalogAccumulator(HAL_DMAHandle handle,
+                                 HAL_AnalogInputHandle aInHandle,
+                                 int32_t* status) {}
+
+void HAL_AddDMADutyCycle(HAL_DMAHandle handle,
+                         HAL_DutyCycleHandle dutyCycleHandle, int32_t* status) {
+}
+
+void HAL_SetDMAExternalTrigger(HAL_DMAHandle handle,
+                               HAL_Handle digitalSourceHandle,
+                               HAL_AnalogTriggerType analogTriggerType,
+                               HAL_Bool rising, HAL_Bool falling,
+                               int32_t* status) {}
+
+void HAL_StartDMA(HAL_DMAHandle handle, int32_t queueDepth, int32_t* status) {}
+void HAL_StopDMA(HAL_DMAHandle handle, int32_t* status) {}
+
+void* HAL_GetDMADirectPointer(HAL_DMAHandle handle) { return nullptr; }
+
+enum HAL_DMAReadStatus HAL_ReadDMADirect(void* dmaPointer,
+                                         HAL_DMASample* dmaSample,
+                                         int32_t timeoutMs,
+                                         int32_t* remainingOut,
+                                         int32_t* status) {
+  return HAL_DMA_ERROR;
+}
+
+enum HAL_DMAReadStatus HAL_ReadDMA(HAL_DMAHandle handle,
+                                   HAL_DMASample* dmaSample, int32_t timeoutMs,
+                                   int32_t* remainingOut, int32_t* status) {
+  return HAL_DMA_ERROR;
+}
+
+// Sampling Code
+uint64_t HAL_GetDMASampleTime(const HAL_DMASample* dmaSample, int32_t* status) {
+  return 0;
+}
+
+int32_t HAL_GetDMASampleEncoderRaw(const HAL_DMASample* dmaSample,
+                                   HAL_EncoderHandle encoderHandle,
+                                   int32_t* status) {
+  return 0;
+}
+
+int32_t HAL_GetDMASampleCounter(const HAL_DMASample* dmaSample,
+                                HAL_CounterHandle counterHandle,
+                                int32_t* status) {
+  return 0;
+}
+
+int32_t HAL_GetDMASampleEncoderPeriodRaw(const HAL_DMASample* dmaSample,
+                                         HAL_EncoderHandle encoderHandle,
+                                         int32_t* status) {
+  return 0;
+}
+
+int32_t HAL_GetDMASampleCounterPeriod(const HAL_DMASample* dmaSample,
+                                      HAL_CounterHandle counterHandle,
+                                      int32_t* status) {
+  return 0;
+}
+HAL_Bool HAL_GetDMASampleDigitalSource(const HAL_DMASample* dmaSample,
+                                       HAL_Handle dSourceHandle,
+                                       int32_t* status) {
+  return 0;
+}
+int32_t HAL_GetDMASampleAnalogInputRaw(const HAL_DMASample* dmaSample,
+                                       HAL_AnalogInputHandle aInHandle,
+                                       int32_t* status) {
+  return 0;
+}
+
+int32_t HAL_GetDMASampleAveragedAnalogInputRaw(const HAL_DMASample* dmaSample,
+                                               HAL_AnalogInputHandle aInHandle,
+                                               int32_t* status) {
+  return 0;
+}
+
+void HAL_GetDMASampleAnalogAccumulator(const HAL_DMASample* dmaSample,
+                                       HAL_AnalogInputHandle aInHandle,
+                                       int64_t* count, int64_t* value,
+                                       int32_t* status) {}
+
+int32_t HAL_GetDMASampleDutyCycleOutputRaw(const HAL_DMASample* dmaSample,
+                                           HAL_DutyCycleHandle dutyCycleHandle,
+                                           int32_t* status) {
+  return 0;
+}
+}  // extern "C"
diff --git a/hal/src/main/native/sim/DriverStation.cpp b/hal/src/main/native/sim/DriverStation.cpp
index a17994e..e8404cf 100644
--- a/hal/src/main/native/sim/DriverStation.cpp
+++ b/hal/src/main/native/sim/DriverStation.cpp
@@ -210,7 +210,11 @@
 }
 #endif
 
-HAL_Bool HAL_IsNewControlData(void) {
+static int& GetThreadLocalLastCount() {
+  // There is a rollover error condition here. At Packet# = n * (uintmax), this
+  // will return false when instead it should return true. However, this at a
+  // 20ms rate occurs once every 2.7 years of DS connected runtime, so not
+  // worth the cycles to check.
 #ifdef __APPLE__
   pthread_once(&lastCountKeyOnce, InitLastCountKey);
   int* lastCountPtr = static_cast<int*>(pthread_getspecific(lastCountKey));
@@ -223,13 +227,43 @@
 #else
   thread_local int lastCount{-1};
 #endif
-  // There is a rollover error condition here. At Packet# = n * (uintmax), this
-  // will return false when instead it should return true. However, this at a
-  // 20ms rate occurs once every 2.7 years of DS connected runtime, so not
-  // worth the cycles to check.
+  return lastCount;
+}
+
+HAL_Bool HAL_WaitForCachedControlDataTimeout(double timeout) {
+  int& lastCount = GetThreadLocalLastCount();
+  std::unique_lock lock(newDSDataAvailableMutex);
+  int currentCount = newDSDataAvailableCounter;
+  if (lastCount != currentCount) {
+    lastCount = currentCount;
+    return true;
+  }
+
+  if (isFinalized.load()) {
+    return false;
+  }
+
+  auto timeoutTime =
+      std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
+
+  while (newDSDataAvailableCounter == currentCount) {
+    if (timeout > 0) {
+      auto timedOut = newDSDataAvailableCond->wait_until(lock, timeoutTime);
+      if (timedOut == std::cv_status::timeout) {
+        return false;
+      }
+    } else {
+      newDSDataAvailableCond->wait(lock);
+    }
+  }
+  return true;
+}
+
+HAL_Bool HAL_IsNewControlData(void) {
+  int& lastCount = GetThreadLocalLastCount();
   int currentCount = 0;
   {
-    std::unique_lock lock(newDSDataAvailableMutex);
+    std::scoped_lock lock(newDSDataAvailableMutex);
     currentCount = newDSDataAvailableCounter;
   }
   if (lastCount == currentCount) return false;
diff --git a/hal/src/main/native/sim/DutyCycle.cpp b/hal/src/main/native/sim/DutyCycle.cpp
new file mode 100644
index 0000000..0e14eeb
--- /dev/null
+++ b/hal/src/main/native/sim/DutyCycle.cpp
@@ -0,0 +1,120 @@
+/*----------------------------------------------------------------------------*/
+/* 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/DutyCycle.h"
+
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/Errors.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+#include "mockdata/DutyCycleDataInternal.h"
+
+using namespace hal;
+
+namespace {
+struct DutyCycle {
+  uint8_t index;
+};
+struct Empty {};
+}  // namespace
+
+static LimitedHandleResource<HAL_DutyCycleHandle, DutyCycle, kNumDutyCycles,
+                             HAL_HandleEnum::DutyCycle>* dutyCycleHandles;
+
+namespace hal {
+namespace init {
+void InitializeDutyCycle() {
+  static LimitedHandleResource<HAL_DutyCycleHandle, DutyCycle, kNumDutyCycles,
+                               HAL_HandleEnum::DutyCycle>
+      dcH;
+  dutyCycleHandles = &dcH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+HAL_DutyCycleHandle HAL_InitializeDutyCycle(HAL_Handle digitalSourceHandle,
+                                            HAL_AnalogTriggerType triggerType,
+                                            int32_t* status) {
+  hal::init::CheckInit();
+
+  HAL_DutyCycleHandle handle = dutyCycleHandles->Allocate();
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+
+  auto dutyCycle = dutyCycleHandles->Get(handle);
+  if (dutyCycle == nullptr) {  // would only occur on thread issue
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  int16_t index = getHandleIndex(handle);
+  SimDutyCycleData[index].digitalChannel = getHandleIndex(digitalSourceHandle);
+  SimDutyCycleData[index].initialized = true;
+  SimDutyCycleData[index].simDevice = 0;
+  dutyCycle->index = index;
+  return handle;
+}
+void HAL_FreeDutyCycle(HAL_DutyCycleHandle dutyCycleHandle) {
+  auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);
+  dutyCycleHandles->Free(dutyCycleHandle);
+  if (dutyCycle == nullptr) return;
+  SimDutyCycleData[dutyCycle->index].initialized = false;
+}
+
+void HAL_SetDutyCycleSimDevice(HAL_EncoderHandle handle,
+                               HAL_SimDeviceHandle device) {
+  auto dutyCycle = dutyCycleHandles->Get(handle);
+  if (dutyCycle == nullptr) return;
+  SimDutyCycleData[dutyCycle->index].simDevice = device;
+}
+
+int32_t HAL_GetDutyCycleFrequency(HAL_DutyCycleHandle dutyCycleHandle,
+                                  int32_t* status) {
+  auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);
+  if (dutyCycle == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return SimDutyCycleData[dutyCycle->index].frequency;
+}
+double HAL_GetDutyCycleOutput(HAL_DutyCycleHandle dutyCycleHandle,
+                              int32_t* status) {
+  auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);
+  if (dutyCycle == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return SimDutyCycleData[dutyCycle->index].output;
+}
+int32_t HAL_GetDutyCycleOutputRaw(HAL_DutyCycleHandle dutyCycleHandle,
+                                  int32_t* status) {
+  auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);
+  if (dutyCycle == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return SimDutyCycleData[dutyCycle->index].output *
+         HAL_GetDutyCycleOutputScaleFactor(dutyCycleHandle, status);
+}
+int32_t HAL_GetDutyCycleOutputScaleFactor(HAL_DutyCycleHandle dutyCycleHandle,
+                                          int32_t* status) {
+  return 4e7 - 1;
+}
+int32_t HAL_GetDutyCycleFPGAIndex(HAL_DutyCycleHandle dutyCycleHandle,
+                                  int32_t* status) {
+  auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);
+  if (dutyCycle == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+  return dutyCycle->index;
+}
+}  // extern "C"
diff --git a/hal/src/main/native/sim/Extensions.cpp b/hal/src/main/native/sim/Extensions.cpp
index e84c354..951ad10 100644
--- a/hal/src/main/native/sim/Extensions.cpp
+++ b/hal/src/main/native/sim/Extensions.cpp
@@ -41,6 +41,11 @@
 }  // namespace init
 }  // namespace hal
 
+static bool& GetShowNotFoundMessage() {
+  static bool showMsg = true;
+  return showMsg;
+}
+
 extern "C" {
 
 int HAL_LoadOneExtension(const char* library) {
@@ -91,8 +96,10 @@
   wpi::SmallVector<wpi::StringRef, 2> libraries;
   const char* e = std::getenv("HALSIM_EXTENSIONS");
   if (!e) {
-    wpi::outs() << "HAL Extensions: No extensions found\n";
-    wpi::outs().flush();
+    if (GetShowNotFoundMessage()) {
+      wpi::outs() << "HAL Extensions: No extensions found\n";
+      wpi::outs().flush();
+    }
     return rc;
   }
   wpi::StringRef env{e};
@@ -105,4 +112,8 @@
   return rc;
 }
 
+void HAL_SetShowExtensionsNotFoundMessages(HAL_Bool showMessage) {
+  GetShowNotFoundMessage() = showMessage;
+}
+
 }  // extern "C"
diff --git a/hal/src/main/native/sim/HAL.cpp b/hal/src/main/native/sim/HAL.cpp
index cf019cf..0dda617 100644
--- a/hal/src/main/native/sim/HAL.cpp
+++ b/hal/src/main/native/sim/HAL.cpp
@@ -25,6 +25,7 @@
 namespace init {
 void InitializeHAL() {
   InitializeAccelerometerData();
+  InitializeAddressableLEDData();
   InitializeAnalogGyroData();
   InitializeAnalogInData();
   InitializeAnalogOutData();
@@ -32,6 +33,7 @@
   InitializeCanData();
   InitializeCANAPI();
   InitializeDigitalPWMData();
+  InitializeDutyCycleData();
   InitializeDIOData();
   InitializeDriverStationData();
   InitializeEncoderData();
@@ -45,6 +47,7 @@
   InitializeSPIAccelerometerData();
   InitializeSPIData();
   InitializeAccelerometer();
+  InitializeAddressableLED();
   InitializeAnalogAccumulator();
   InitializeAnalogGyro();
   InitializeAnalogInput();
@@ -56,6 +59,7 @@
   InitializeCounter();
   InitializeDigitalInternal();
   InitializeDIO();
+  InitializeDutyCycle();
   InitializeDriverStation();
   InitializeEncoder();
   InitializeExtensions();
@@ -199,6 +203,12 @@
       return HAL_PWM_SCALE_ERROR_MESSAGE;
     case HAL_CAN_TIMEOUT:
       return HAL_CAN_TIMEOUT_MESSAGE;
+    case HAL_SIM_NOT_SUPPORTED:
+      return HAL_SIM_NOT_SUPPORTED_MESSAGE;
+    case HAL_CAN_BUFFER_OVERRUN:
+      return HAL_CAN_BUFFER_OVERRUN_MESSAGE;
+    case HAL_LED_CHANNEL_ERROR:
+      return HAL_LED_CHANNEL_ERROR_MESSAGE;
     default:
       return "Unknown error status";
   }
@@ -216,6 +226,28 @@
 
 uint64_t HAL_GetFPGATime(int32_t* status) { return hal::GetFPGATime(); }
 
+uint64_t HAL_ExpandFPGATime(uint32_t unexpanded_lower, int32_t* status) {
+  // Capture the current FPGA time.  This will give us the upper half of the
+  // clock.
+  uint64_t fpga_time = HAL_GetFPGATime(status);
+  if (*status != 0) return 0;
+
+  // Now, we need to detect the case where the lower bits rolled over after we
+  // sampled.  In that case, the upper bits will be 1 bigger than they should
+  // be.
+
+  // Break it into lower and upper portions.
+  uint32_t lower = fpga_time & 0xffffffffull;
+  uint64_t upper = (fpga_time >> 32) & 0xffffffff;
+
+  // The time was sampled *before* the current time, so roll it back.
+  if (lower < unexpanded_lower) {
+    --upper;
+  }
+
+  return (upper << 32) + static_cast<uint64_t>(unexpanded_lower);
+}
+
 HAL_Bool HAL_GetFPGAButton(int32_t* status) {
   return SimRoboRioData[0].fpgaButton;
 }
diff --git a/hal/src/main/native/sim/HALInitializer.h b/hal/src/main/native/sim/HALInitializer.h
index 4c91b40..c08df73 100644
--- a/hal/src/main/native/sim/HALInitializer.h
+++ b/hal/src/main/native/sim/HALInitializer.h
@@ -19,6 +19,7 @@
 }
 
 extern void InitializeAccelerometerData();
+extern void InitializeAddressableLEDData();
 extern void InitializeAnalogGyroData();
 extern void InitializeAnalogInData();
 extern void InitializeAnalogOutData();
@@ -26,7 +27,9 @@
 extern void InitializeCanData();
 extern void InitializeCANAPI();
 extern void InitializeDigitalPWMData();
+extern void InitializeDutyCycleData();
 extern void InitializeDIOData();
+extern void InitializeDutyCycle();
 extern void InitializeDriverStationData();
 extern void InitializeEncoderData();
 extern void InitializeI2CData();
@@ -39,6 +42,7 @@
 extern void InitializeSPIAccelerometerData();
 extern void InitializeSPIData();
 extern void InitializeAccelerometer();
+extern void InitializeAddressableLED();
 extern void InitializeAnalogAccumulator();
 extern void InitializeAnalogGyro();
 extern void InitializeAnalogInput();
diff --git a/hal/src/main/native/sim/MockHooks.cpp b/hal/src/main/native/sim/MockHooks.cpp
index 25c1d9f..59086ae 100644
--- a/hal/src/main/native/sim/MockHooks.cpp
+++ b/hal/src/main/native/sim/MockHooks.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -13,10 +13,12 @@
 #include <wpi/timestamp.h>
 
 #include "MockHooksInternal.h"
+#include "NotifierInternal.h"
 
 static std::atomic<bool> programStarted{false};
 
 static std::atomic<uint64_t> programStartTime{0};
+static std::atomic<uint64_t> programPauseTime{0};
 
 namespace hal {
 namespace init {
@@ -25,12 +27,32 @@
 }  // namespace hal
 
 namespace hal {
-void RestartTiming() { programStartTime = wpi::Now(); }
+void RestartTiming() {
+  programStartTime = wpi::Now();
+  if (programPauseTime != 0) programPauseTime = programStartTime.load();
+}
+
+void PauseTiming() {
+  if (programPauseTime == 0) programPauseTime = wpi::Now();
+}
+
+void ResumeTiming() {
+  if (programPauseTime != 0) {
+    programStartTime += wpi::Now() - programPauseTime;
+    programPauseTime = 0;
+  }
+}
+
+bool IsTimingPaused() { return programPauseTime != 0; }
+
+void StepTiming(uint64_t delta) {
+  if (programPauseTime != 0) programPauseTime += delta;
+}
 
 int64_t GetFPGATime() {
-  auto now = wpi::Now();
-  auto currentTime = now - programStartTime;
-  return currentTime;
+  uint64_t curTime = programPauseTime;
+  if (curTime == 0) curTime = wpi::Now();
+  return curTime - programStartTime;
 }
 
 double GetFPGATimestamp() { return GetFPGATime() * 1.0e-6; }
@@ -56,4 +78,21 @@
 HAL_Bool HALSIM_GetProgramStarted(void) { return GetProgramStarted(); }
 
 void HALSIM_RestartTiming(void) { RestartTiming(); }
+
+void HALSIM_PauseTiming(void) {
+  PauseTiming();
+  PauseNotifiers();
+}
+
+void HALSIM_ResumeTiming(void) {
+  ResumeTiming();
+  ResumeNotifiers();
+}
+
+HAL_Bool HALSIM_IsTimingPaused(void) { return IsTimingPaused(); }
+
+void HALSIM_StepTiming(uint64_t delta) {
+  StepTiming(delta);
+  WakeupNotifiers();
+}
 }  // extern "C"
diff --git a/hal/src/main/native/sim/MockHooksInternal.h b/hal/src/main/native/sim/MockHooksInternal.h
index e8c09a9..a69e9bf 100644
--- a/hal/src/main/native/sim/MockHooksInternal.h
+++ b/hal/src/main/native/sim/MockHooksInternal.h
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -14,6 +14,14 @@
 namespace hal {
 void RestartTiming();
 
+void PauseTiming();
+
+void ResumeTiming();
+
+bool IsTimingPaused();
+
+void StepTiming(uint64_t delta);
+
 int64_t GetFPGATime();
 
 double GetFPGATimestamp();
diff --git a/hal/src/main/native/sim/Notifier.cpp b/hal/src/main/native/sim/Notifier.cpp
index 579540c..211f7b2 100644
--- a/hal/src/main/native/sim/Notifier.cpp
+++ b/hal/src/main/native/sim/Notifier.cpp
@@ -7,21 +7,27 @@
 
 #include "hal/Notifier.h"
 
+#include <atomic>
 #include <chrono>
+#include <cstdio>
+#include <cstring>
+#include <string>
 
 #include <wpi/condition_variable.h>
 #include <wpi/mutex.h>
 #include <wpi/timestamp.h>
 
 #include "HALInitializer.h"
+#include "NotifierInternal.h"
 #include "hal/HAL.h"
 #include "hal/cpp/fpga_clock.h"
 #include "hal/handles/UnlimitedHandleResource.h"
+#include "mockdata/NotifierData.h"
 
 namespace {
 struct Notifier {
+  std::string name;
   uint64_t waitTime;
-  bool updatedAlarm = false;
   bool active = true;
   bool running = false;
   wpi::mutex mutex;
@@ -48,6 +54,7 @@
 };
 
 static NotifierHandleContainer* notifierHandles;
+static std::atomic<bool> notifiersPaused{false};
 
 namespace hal {
 namespace init {
@@ -56,6 +63,19 @@
   notifierHandles = &nH;
 }
 }  // namespace init
+
+void PauseNotifiers() { notifiersPaused = true; }
+
+void ResumeNotifiers() {
+  notifiersPaused = false;
+  WakeupNotifiers();
+}
+
+void WakeupNotifiers() {
+  notifierHandles->ForEach([](HAL_NotifierHandle handle, Notifier* notifier) {
+    notifier->cond.notify_all();
+  });
+}
 }  // namespace hal
 
 extern "C" {
@@ -71,6 +91,14 @@
   return handle;
 }
 
+void HAL_SetNotifierName(HAL_NotifierHandle notifierHandle, const char* name,
+                         int32_t* status) {
+  auto notifier = notifierHandles->Get(notifierHandle);
+  if (!notifier) return;
+  std::scoped_lock lock(notifier->mutex);
+  notifier->name = name;
+}
+
 void HAL_StopNotifier(HAL_NotifierHandle notifierHandle, int32_t* status) {
   auto notifier = notifierHandles->Get(notifierHandle);
   if (!notifier) return;
@@ -105,7 +133,6 @@
     std::scoped_lock lock(notifier->mutex);
     notifier->waitTime = triggerTime;
     notifier->running = true;
-    notifier->updatedAlarm = true;
   }
 
   // We wake up any waiters to change how long they're sleeping for
@@ -131,29 +158,66 @@
   std::unique_lock lock(notifier->mutex);
   while (notifier->active) {
     double waitTime;
-    if (!notifier->running) {
+    if (!notifier->running || notifiersPaused) {
       waitTime = (HAL_GetFPGATime(status) * 1e-6) + 1000.0;
       // If not running, wait 1000 seconds
     } else {
       waitTime = notifier->waitTime * 1e-6;
     }
 
-    // Don't wait twice
-    notifier->updatedAlarm = false;
-
     auto timeoutTime =
         hal::fpga_clock::epoch() + std::chrono::duration<double>(waitTime);
     notifier->cond.wait_until(lock, timeoutTime);
-    if (notifier->updatedAlarm) {
-      notifier->updatedAlarm = false;
-      continue;
-    }
     if (!notifier->running) continue;
     if (!notifier->active) break;
+    uint64_t curTime = HAL_GetFPGATime(status);
+    if (curTime < notifier->waitTime) continue;
     notifier->running = false;
-    return HAL_GetFPGATime(status);
+    return curTime;
   }
   return 0;
 }
 
+uint64_t HALSIM_GetNextNotifierTimeout(void) {
+  uint64_t timeout = UINT64_MAX;
+  notifierHandles->ForEach([&](HAL_NotifierHandle, Notifier* notifier) {
+    std::scoped_lock lock(notifier->mutex);
+    if (notifier->active && notifier->running && timeout > notifier->waitTime)
+      timeout = notifier->waitTime;
+  });
+  return timeout;
+}
+
+int32_t HALSIM_GetNumNotifiers(void) {
+  int32_t count = 0;
+  notifierHandles->ForEach([&](HAL_NotifierHandle, Notifier* notifier) {
+    std::scoped_lock lock(notifier->mutex);
+    if (notifier->active) ++count;
+  });
+  return count;
+}
+
+int32_t HALSIM_GetNotifierInfo(struct HALSIM_NotifierInfo* arr, int32_t size) {
+  int32_t num = 0;
+  notifierHandles->ForEach([&](HAL_NotifierHandle handle, Notifier* notifier) {
+    std::scoped_lock lock(notifier->mutex);
+    if (!notifier->active) return;
+    if (num < size) {
+      arr[num].handle = handle;
+      if (notifier->name.empty()) {
+        std::snprintf(arr[num].name, sizeof(arr[num].name), "Notifier%d",
+                      static_cast<int>(getHandleIndex(handle)));
+      } else {
+        std::strncpy(arr[num].name, notifier->name.c_str(),
+                     sizeof(arr[num].name));
+        arr[num].name[sizeof(arr[num].name) - 1] = '\0';
+      }
+      arr[num].timeout = notifier->waitTime;
+      arr[num].running = notifier->running;
+    }
+    ++num;
+  });
+  return num;
+}
+
 }  // extern "C"
diff --git a/hal/src/main/native/sim/NotifierInternal.h b/hal/src/main/native/sim/NotifierInternal.h
new file mode 100644
index 0000000..84232d2
--- /dev/null
+++ b/hal/src/main/native/sim/NotifierInternal.h
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace hal {
+void PauseNotifiers();
+void ResumeNotifiers();
+void WakeupNotifiers();
+}  // namespace hal
diff --git a/hal/src/main/native/sim/PDP.cpp b/hal/src/main/native/sim/PDP.cpp
index 07f4dcd..dbe09d4 100644
--- a/hal/src/main/native/sim/PDP.cpp
+++ b/hal/src/main/native/sim/PDP.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -78,6 +78,18 @@
   }
   return SimPDPData[module].current[channel];
 }
+void HAL_GetPDPAllChannelCurrents(HAL_PDPHandle handle, double* currents,
+                                  int32_t* status) {
+  auto module = hal::can::GetCANModuleFromHandle(handle, status);
+  if (*status != 0) {
+    return;
+  }
+
+  auto& data = SimPDPData[module];
+  for (int i = 0; i < kNumPDPChannels; i++) {
+    currents[i] = data.current[i];
+  }
+}
 double HAL_GetPDPTotalCurrent(HAL_PDPHandle handle, int32_t* status) {
   return 0.0;
 }
diff --git a/hal/src/main/native/sim/Ports.cpp b/hal/src/main/native/sim/Ports.cpp
index f50304f..2f670b3 100644
--- a/hal/src/main/native/sim/Ports.cpp
+++ b/hal/src/main/native/sim/Ports.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -36,5 +36,6 @@
 int32_t HAL_GetNumSolenoidChannels(void) { return kNumSolenoidChannels; }
 int32_t HAL_GetNumPDPModules(void) { return kNumPDPModules; }
 int32_t HAL_GetNumPDPChannels(void) { return kNumPDPChannels; }
-int32_t HAL_GetNumCanTalons(void) { return kNumCanTalons; }
+int32_t HAL_GetNumDutyCycles(void) { return kNumDutyCycles; }
+int32_t HAL_GetNumAddressableLEDs(void) { return kNumAddressableLEDs; }
 }  // extern "C"
diff --git a/hal/src/main/native/sim/PortsInternal.h b/hal/src/main/native/sim/PortsInternal.h
index 0b899f7..cfbf1e7 100644
--- a/hal/src/main/native/sim/PortsInternal.h
+++ b/hal/src/main/native/sim/PortsInternal.h
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -28,5 +28,6 @@
 constexpr int32_t kNumSolenoidChannels = 8;
 constexpr int32_t kNumPDPModules = 63;
 constexpr int32_t kNumPDPChannels = 16;
-constexpr int32_t kNumCanTalons = 63;
+constexpr int32_t kNumDutyCycles = 8;
+constexpr int32_t kNumAddressableLEDs = 1;
 }  // namespace hal
diff --git a/hal/src/main/native/sim/Solenoid.cpp b/hal/src/main/native/sim/Solenoid.cpp
index d3f0c5d..46bd285 100644
--- a/hal/src/main/native/sim/Solenoid.cpp
+++ b/hal/src/main/native/sim/Solenoid.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2016-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -120,6 +120,15 @@
 
   HALSIM_SetPCMSolenoidOutput(port->module, port->channel, value);
 }
+
+void HAL_SetAllSolenoids(int32_t module, int32_t state, int32_t* status) {
+  for (int i = 0; i < kNumSolenoidChannels; i++) {
+    int set = state & 1;
+    HALSIM_SetPCMSolenoidOutput(module, i, set);
+    state >>= 1;
+  }
+}
+
 int32_t HAL_GetPCMSolenoidBlackList(int32_t module, int32_t* status) {
   return 0;
 }
diff --git a/hal/src/main/native/sim/jni/AddressableLEDDataJNI.cpp b/hal/src/main/native/sim/jni/AddressableLEDDataJNI.cpp
new file mode 100644
index 0000000..530eae2
--- /dev/null
+++ b/hal/src/main/native/sim/jni/AddressableLEDDataJNI.cpp
@@ -0,0 +1,293 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "CallbackStore.h"
+#include "ConstBufferCallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI.h"
+#include "mockdata/AddressableLEDData.h"
+
+static_assert(sizeof(jbyte) * 4 == sizeof(HAL_AddressableLEDData));
+
+using namespace wpi::java;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    registerInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_registerInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(
+      env, index, callback, initialNotify,
+      &HALSIM_RegisterAddressableLEDInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    cancelInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_cancelInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAddressableLEDInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    getInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_getInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAddressableLEDInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    setInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_setInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetAddressableLEDInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    registerOutputPortCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_registerOutputPortCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(
+      env, index, callback, initialNotify,
+      &HALSIM_RegisterAddressableLEDOutputPortCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    cancelOutputPortCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_cancelOutputPortCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAddressableLEDOutputPortCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    getOutputPort
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_getOutputPort
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAddressableLEDOutputPort(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    setOutputPort
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_setOutputPort
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetAddressableLEDOutputPort(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    registerLengthCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_registerLengthCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAddressableLEDLengthCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    cancelLengthCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_cancelLengthCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAddressableLEDLengthCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    getLength
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_getLength
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAddressableLEDLength(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    setLength
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_setLength
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetAddressableLEDLength(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    registerRunningCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_registerRunningCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAddressableLEDRunningCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    cancelRunningCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_cancelRunningCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAddressableLEDRunningCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    getRunning
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_getRunning
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAddressableLEDRunning(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    setRunning
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_setRunning
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetAddressableLEDRunning(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    registerDataCallback
+ * Signature: (ILjava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_registerDataCallback
+  (JNIEnv* env, jclass, jint index, jobject callback)
+{
+  return sim::AllocateConstBufferCallback(
+      env, index, callback, &HALSIM_RegisterAddressableLEDDataCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    cancelDataCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_cancelDataCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  sim::FreeConstBufferCallback(env, handle, index,
+                               &HALSIM_CancelAddressableLEDDataCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    getData
+ * Signature: (I)[B
+ */
+JNIEXPORT jbyteArray JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_getData
+  (JNIEnv* env, jclass, jint index)
+{
+  auto data =
+      std::make_unique<HAL_AddressableLEDData[]>(HAL_kAddressableLEDMaxLength);
+  int32_t length = HALSIM_GetAddressableLEDData(index, data.get());
+  return MakeJByteArray(
+      env, wpi::ArrayRef(reinterpret_cast<jbyte*>(data.get()), length * 4));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    setData
+ * Signature: (I[B)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_setData
+  (JNIEnv* env, jclass, jint index, jbyteArray arr)
+{
+  JByteArrayRef jArrRef{env, arr};
+  auto arrRef = jArrRef.array();
+  HALSIM_SetAddressableLEDData(
+      index, reinterpret_cast<const HAL_AddressableLEDData*>(arrRef.data()),
+      arrRef.size() / 4);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AddressableLEDDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetAddressableLEDData(index);
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/sim/jni/DutyCycleDataJNI.cpp b/hal/src/main/native/sim/jni/DutyCycleDataJNI.cpp
new file mode 100644
index 0000000..d746ce1
--- /dev/null
+++ b/hal/src/main/native/sim/jni/DutyCycleDataJNI.cpp
@@ -0,0 +1,178 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI.h"
+#include "mockdata/DutyCycleData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI
+ * Method:    registerInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_registerInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterDutyCycleInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI
+ * Method:    cancelInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_cancelInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelDutyCycleInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI
+ * Method:    getInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_getInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetDutyCycleInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI
+ * Method:    setInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_setInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetDutyCycleInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI
+ * Method:    registerFrequencyCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_registerFrequencyCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterDutyCycleFrequencyCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI
+ * Method:    cancelFrequencyCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_cancelFrequencyCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelDutyCycleFrequencyCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI
+ * Method:    getFrequency
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_getFrequency
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetDutyCycleFrequency(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI
+ * Method:    setFrequency
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_setFrequency
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetDutyCycleFrequency(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI
+ * Method:    registerOutputCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_registerOutputCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterDutyCycleOutputCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI
+ * Method:    cancelOutputCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_cancelOutputCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelDutyCycleOutputCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI
+ * Method:    getOutput
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_getOutput
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetDutyCycleOutput(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI
+ * Method:    setOutput
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_setOutput
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetDutyCycleOutput(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DutyCycleDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetDutyCycleData(index);
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/sim/jni/NotifierDataJNI.cpp b/hal/src/main/native/sim/jni/NotifierDataJNI.cpp
new file mode 100644
index 0000000..b59b6e0
--- /dev/null
+++ b/hal/src/main/native/sim/jni/NotifierDataJNI.cpp
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "edu_wpi_first_hal_sim_mockdata_NotifierDataJNI.h"
+#include "mockdata/NotifierData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_NotifierDataJNI
+ * Method:    getNextTimeout
+ * Signature: ()J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_NotifierDataJNI_getNextTimeout
+  (JNIEnv*, jclass)
+{
+  return HALSIM_GetNextNotifierTimeout();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_NotifierDataJNI
+ * Method:    getNumNotifiers
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_NotifierDataJNI_getNumNotifiers
+  (JNIEnv*, jclass)
+{
+  return HALSIM_GetNumNotifiers();
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/sim/jni/SimulatorJNI.cpp b/hal/src/main/native/sim/jni/SimulatorJNI.cpp
index bba8f01..9226f91 100644
--- a/hal/src/main/native/sim/jni/SimulatorJNI.cpp
+++ b/hal/src/main/native/sim/jni/SimulatorJNI.cpp
@@ -144,6 +144,54 @@
 
 /*
  * Class:     edu_wpi_first_hal_sim_mockdata_SimulatorJNI
+ * Method:    pauseTiming
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimulatorJNI_pauseTiming
+  (JNIEnv*, jclass)
+{
+  HALSIM_PauseTiming();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimulatorJNI
+ * Method:    resumeTiming
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimulatorJNI_resumeTiming
+  (JNIEnv*, jclass)
+{
+  HALSIM_ResumeTiming();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimulatorJNI
+ * Method:    isTimingPaused
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimulatorJNI_isTimingPaused
+  (JNIEnv*, jclass)
+{
+  return HALSIM_IsTimingPaused();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimulatorJNI
+ * Method:    stepTiming
+ * Signature: (J)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimulatorJNI_stepTiming
+  (JNIEnv*, jclass, jlong delta)
+{
+  HALSIM_StepTiming(delta);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimulatorJNI
  * Method:    resetHandles
  * Signature: ()V
  */
diff --git a/hal/src/main/native/sim/mockdata/AddressableLEDData.cpp b/hal/src/main/native/sim/mockdata/AddressableLEDData.cpp
new file mode 100644
index 0000000..5b44eaf
--- /dev/null
+++ b/hal/src/main/native/sim/mockdata/AddressableLEDData.cpp
@@ -0,0 +1,96 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <algorithm>
+#include <cstring>
+
+#include "../PortsInternal.h"
+#include "AddressableLEDDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeAddressableLEDData() {
+  static AddressableLEDData sad[kNumAddressableLEDs];
+  ::hal::SimAddressableLEDData = sad;
+}
+}  // namespace init
+}  // namespace hal
+
+AddressableLEDData* hal::SimAddressableLEDData;
+
+void AddressableLEDData::ResetData() {
+  initialized.Reset(false);
+  outputPort.Reset(-1);
+  length.Reset(1);
+  running.Reset(false);
+  data.Reset();
+}
+
+void AddressableLEDData::SetData(const HAL_AddressableLEDData* d, int32_t len) {
+  len = (std::min)(HAL_kAddressableLEDMaxLength, len);
+  {
+    std::scoped_lock lock(m_dataMutex);
+    std::memcpy(m_data, d, len * sizeof(d[0]));
+  }
+  data(reinterpret_cast<const uint8_t*>(d), len * sizeof(d[0]));
+}
+
+int32_t AddressableLEDData::GetData(HAL_AddressableLEDData* d) {
+  std::scoped_lock lock(m_dataMutex);
+  int32_t len = length;
+  if (d) std::memcpy(d, m_data, len * sizeof(d[0]));
+  return len;
+}
+
+extern "C" {
+void HALSIM_ResetAddressableLEDData(int32_t index) {
+  SimAddressableLEDData[index].ResetData();
+}
+
+int32_t HALSIM_GetAddressableLEDData(int32_t index,
+                                     struct HAL_AddressableLEDData* data) {
+  return SimAddressableLEDData[index].GetData(data);
+}
+
+void HALSIM_SetAddressableLEDData(int32_t index,
+                                  const struct HAL_AddressableLEDData* data,
+                                  int32_t length) {
+  SimAddressableLEDData[index].SetData(data, length);
+}
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                         \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, AddressableLED##CAPINAME, \
+                               SimAddressableLEDData, LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, Initialized, initialized)
+DEFINE_CAPI(int32_t, OutputPort, outputPort)
+DEFINE_CAPI(int32_t, Length, length)
+DEFINE_CAPI(HAL_Bool, Running, running)
+
+#undef DEFINE_CAPI
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                                \
+  HAL_SIMCALLBACKREGISTRY_DEFINE_CAPI(TYPE, HALSIM, AddressableLED##CAPINAME, \
+                                      SimAddressableLEDData, LOWERNAME)
+
+DEFINE_CAPI(HAL_ConstBufferCallback, Data, data)
+
+#define REGISTER(NAME)                                                \
+  SimAddressableLEDData[index].NAME.RegisterCallback(callback, param, \
+                                                     initialNotify)
+
+void HALSIM_RegisterAddressableLEDAllCallbacks(int32_t index,
+                                               HAL_NotifyCallback callback,
+                                               void* param,
+                                               HAL_Bool initialNotify) {
+  REGISTER(initialized);
+  REGISTER(outputPort);
+  REGISTER(length);
+  REGISTER(running);
+}
+}  // extern "C"
diff --git a/hal/src/main/native/sim/mockdata/AddressableLEDDataInternal.h b/hal/src/main/native/sim/mockdata/AddressableLEDDataInternal.h
new file mode 100644
index 0000000..9d6e215
--- /dev/null
+++ b/hal/src/main/native/sim/mockdata/AddressableLEDDataInternal.h
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <vector>
+
+#include <wpi/spinlock.h>
+
+#include "mockdata/AddressableLEDData.h"
+#include "mockdata/SimCallbackRegistry.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class AddressableLEDData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
+  HAL_SIMDATAVALUE_DEFINE_NAME(OutputPort)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Length)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Running)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Data)
+
+  wpi::recursive_spinlock m_dataMutex;
+  HAL_AddressableLEDData m_data[HAL_kAddressableLEDMaxLength];
+
+ public:
+  void SetData(const HAL_AddressableLEDData* d, int32_t len);
+  int32_t GetData(HAL_AddressableLEDData* d);
+
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{
+      false};
+  SimDataValue<int32_t, HAL_MakeInt, GetOutputPortName> outputPort{-1};
+  SimDataValue<int32_t, HAL_MakeInt, GetLengthName> length{1};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetRunningName> running{false};
+  SimCallbackRegistry<HAL_ConstBufferCallback, GetDataName> data;
+
+  void ResetData();
+};
+extern AddressableLEDData* SimAddressableLEDData;
+}  // namespace hal
diff --git a/hal/src/main/native/sim/mockdata/DutyCycleData.cpp b/hal/src/main/native/sim/mockdata/DutyCycleData.cpp
new file mode 100644
index 0000000..04806e0
--- /dev/null
+++ b/hal/src/main/native/sim/mockdata/DutyCycleData.cpp
@@ -0,0 +1,63 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "../PortsInternal.h"
+#include "DutyCycleDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeDutyCycleData() {
+  static DutyCycleData sed[kNumDutyCycles];
+  ::hal::SimDutyCycleData = sed;
+}
+}  // namespace init
+}  // namespace hal
+
+DutyCycleData* hal::SimDutyCycleData;
+
+void DutyCycleData::ResetData() {
+  digitalChannel = 0;
+  initialized.Reset(false);
+  simDevice = 0;
+  frequency.Reset(0);
+  output.Reset(0);
+}
+
+extern "C" {
+void HALSIM_ResetDutyCycleData(int32_t index) {
+  SimDutyCycleData[index].ResetData();
+}
+int32_t HALSIM_GetDutyCycleDigitalChannel(int32_t index) {
+  return SimDutyCycleData[index].digitalChannel;
+}
+
+HAL_SimDeviceHandle HALSIM_GetDutyCycleSimDevice(int32_t index) {
+  return SimDutyCycleData[index].simDevice;
+}
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                    \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, DutyCycle##CAPINAME, \
+                               SimDutyCycleData, LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, Initialized, initialized)
+DEFINE_CAPI(int32_t, Frequency, frequency)
+DEFINE_CAPI(double, Output, output)
+
+#define REGISTER(NAME) \
+  SimDutyCycleData[index].NAME.RegisterCallback(callback, param, initialNotify)
+
+void HALSIM_RegisterDutyCycleAllCallbacks(int32_t index,
+                                          HAL_NotifyCallback callback,
+                                          void* param, HAL_Bool initialNotify) {
+  REGISTER(initialized);
+  REGISTER(frequency);
+  REGISTER(output);
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/sim/mockdata/DutyCycleDataInternal.h b/hal/src/main/native/sim/mockdata/DutyCycleDataInternal.h
new file mode 100644
index 0000000..2f98b07
--- /dev/null
+++ b/hal/src/main/native/sim/mockdata/DutyCycleDataInternal.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+#include <limits>
+
+#include "mockdata/DutyCycleData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class DutyCycleData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Output)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Frequency)
+
+ public:
+  std::atomic<int32_t> digitalChannel{0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{
+      false};
+  std::atomic<HAL_SimDeviceHandle> simDevice;
+  SimDataValue<int32_t, HAL_MakeInt, GetFrequencyName> frequency{0};
+  SimDataValue<double, HAL_MakeDouble, GetOutputName> output{0};
+
+  virtual void ResetData();
+};
+extern DutyCycleData* SimDutyCycleData;
+}  // namespace hal
diff --git a/hal/src/main/native/sim/mockdata/PCMData.cpp b/hal/src/main/native/sim/mockdata/PCMData.cpp
index df68e04..6193b05 100644
--- a/hal/src/main/native/sim/mockdata/PCMData.cpp
+++ b/hal/src/main/native/sim/mockdata/PCMData.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -49,6 +49,23 @@
 DEFINE_CAPI(HAL_Bool, PressureSwitch, pressureSwitch)
 DEFINE_CAPI(double, CompressorCurrent, compressorCurrent)
 
+void HALSIM_GetPCMAllSolenoids(int32_t index, uint8_t* values) {
+  auto& data = SimPCMData[index].solenoidOutput;
+  uint8_t ret = 0;
+  for (int i = 0; i < kNumSolenoidChannels; i++) {
+    ret |= (data[i] << i);
+  }
+  *values = ret;
+}
+
+void HALSIM_SetPCMAllSolenoids(int32_t index, uint8_t values) {
+  auto& data = SimPCMData[index].solenoidOutput;
+  for (int i = 0; i < kNumSolenoidChannels; i++) {
+    data[i] = (values & 0x1) != 0;
+    values >>= 1;
+  }
+}
+
 #define REGISTER(NAME) \
   SimPCMData[index].NAME.RegisterCallback(callback, param, initialNotify)
 
diff --git a/hal/src/main/native/sim/mockdata/PDPData.cpp b/hal/src/main/native/sim/mockdata/PDPData.cpp
index 9c6143e..1c150bb 100644
--- a/hal/src/main/native/sim/mockdata/PDPData.cpp
+++ b/hal/src/main/native/sim/mockdata/PDPData.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
+/* 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.                                                               */
@@ -42,6 +42,20 @@
 HAL_SIMDATAVALUE_DEFINE_CAPI_CHANNEL(double, HALSIM, PDPCurrent, SimPDPData,
                                      current)
 
+void HALSIM_GetPDPAllCurrents(int32_t index, double* currents) {
+  auto& data = SimPDPData[index].current;
+  for (int i = 0; i < kNumPDPChannels; i++) {
+    currents[i] = data[i];
+  }
+}
+
+void HALSIM_SetPDPAllCurrents(int32_t index, const double* currents) {
+  auto& data = SimPDPData[index].current;
+  for (int i = 0; i < kNumPDPChannels; i++) {
+    data[i] = currents[i];
+  }
+}
+
 #define REGISTER(NAME) \
   SimPDPData[index].NAME.RegisterCallback(callback, param, initialNotify)
 
diff --git a/hal/src/test/java/edu/wpi/first/hal/sim/SimDeviceSimTest.java b/hal/src/test/java/edu/wpi/first/hal/sim/SimDeviceSimTest.java
new file mode 100644
index 0000000..29452a0
--- /dev/null
+++ b/hal/src/test/java/edu/wpi/first/hal/sim/SimDeviceSimTest.java
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import org.junit.jupiter.api.Test;
+
+import edu.wpi.first.hal.SimBoolean;
+import edu.wpi.first.hal.SimDevice;
+
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+class SimDeviceSimTest {
+  @Test
+  void testBasic() {
+    SimDevice dev = SimDevice.create("test");
+    SimBoolean devBool = dev.createBoolean("bool", false, false);
+
+    SimDeviceSim sim = new SimDeviceSim("test");
+    SimBoolean simBool = sim.getBoolean("bool");
+
+    assertFalse(simBool.get());
+    simBool.set(true);
+    assertTrue(devBool.get());
+  }
+}
diff --git a/hal/src/test/native/cpp/mockdata/DriverStationDataTests.cpp b/hal/src/test/native/cpp/mockdata/DriverStationDataTests.cpp
index 35c0d54..5505c06 100644
--- a/hal/src/test/native/cpp/mockdata/DriverStationDataTests.cpp
+++ b/hal/src/test/native/cpp/mockdata/DriverStationDataTests.cpp
@@ -1,5 +1,5 @@
 /*----------------------------------------------------------------------------*/
-/* Copyright (c) 2015-2018 FIRST. All Rights Reserved.                        */
+/* Copyright (c) 2015-2019 FIRST. All Rights Reserved.                        */
 /* Open Source Software - may be modified and shared by FRC teams. The code   */
 /* must be accompanied by the FIRST BSD license file in the root directory of */
 /* the project.                                                               */
@@ -50,7 +50,7 @@
   int joystickUnderTest = 4;
   set_axes.count = 5;
   for (int i = 0; i < set_axes.count; ++i) {
-    set_axes.axes[i] = i * .125;
+    set_axes.axes[i] = i * 0.125;
   }
 
   set_povs.count = 3;
diff --git a/hal/src/test/native/cpp/sim/SimDeviceSimTest.cpp b/hal/src/test/native/cpp/sim/SimDeviceSimTest.cpp
new file mode 100644
index 0000000..ba0646d
--- /dev/null
+++ b/hal/src/test/native/cpp/sim/SimDeviceSimTest.cpp
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2019 FIRST. All Rights Reserved.                             */
+/* Open Source Software - may be modified and shared by FRC teams. The code   */
+/* must be accompanied by the FIRST BSD license file in the root directory of */
+/* the project.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#include <wpi/StringRef.h>
+
+#include "gtest/gtest.h"
+#include "hal/SimDevice.h"
+#include "simulation/SimDeviceSim.h"
+
+using namespace frc::sim;
+
+namespace hal {
+
+TEST(SimDeviceSimTests, TestBasic) {
+  SimDevice dev{"test"};
+  SimBoolean devBool = dev.CreateBoolean("bool", false, false);
+
+  SimDeviceSim sim{"test"};
+  SimBoolean simBool = sim.GetBoolean("bool");
+  EXPECT_FALSE(simBool.Get());
+  simBool.Set(true);
+  EXPECT_TRUE(devBool.Get());
+}
+
+TEST(SimDeviceSimTests, TestEnumerateDevices) {
+  SimDevice dev{"test"};
+
+  bool foundit = false;
+  SimDeviceSim::EnumerateDevices(
+      "te", [&](const char* name, HAL_SimDeviceHandle handle) {
+        if (wpi::StringRef(name) == "test") foundit = true;
+      });
+  EXPECT_TRUE(foundit);
+}
+
+}  // namespace hal