Squashed 'third_party/allwpilib_2019/' changes from 99e4f7dd2..c36bbcc9a

936627bd9 wpilibc: Remove direct CameraServer dependency (#1989)
8e333c0aa Use FPGA Time instead of wall clock time for odometry (#1996)
d4430b765 Gearsbot example: Use standard argument order (#1995)
75438ab2c Add RamseteCommand (#1951)
989df1b46 Bump Native Utils and OpenCV dependencies (#1993)
dbc33b61e Fix Timer usage in TrapezoidProfileCommand (#1992)
79f8c5644 Add TrapezoidProfileCommand (#1962)
9440edf2b Refactor TrajectoryGenerator (#1972)
73a30182c Add frc2::Timer (#1968)
36ea865ed Add toString for geometry and trajectory classes (#1991)
cbe05e7e8 Update ProfiledPIDController API (#1967)
d04eb3546 Deprecate old PID classes (#1964)
02264db69 Add JNI dependencies to myRobotCpp (#1980)
2a76c996e Use VID/PID detection for PS3Eye (#1977)
a3820bbdf Remove HAL_BaseInitialize (#1981)
a83fb4793 Update to 2020v5 image (#1983)
4b0ed910e Make SwerveDriveKinematics.toChassisSpeeds() public (#1976)
103c1b121 Remove DS caching from the HAL level (#1971)
6635ea75e Fix NPE in SendableRegistry.foreachLiveWindow() (#1974)
cfe23c5cd Fix grammar error in comment for configureButtonBindings (#1969)
4bde2654e Fix mac azure build (#1973)
4f034e6c1 generateTrajectory: default reversed param to false (#1953)
acf960f72 Sim GUI: Add option to disable outputs on DS disable
2d3dac99f Sim GUI: Handle low resolutions and scale default window positions
07c86e0cd Sim GUI: Support High DPI monitors
46ad95512 SimDeviceData: Add missing null check
5bce489b9 Add ProggyDotted font to imgui (both cmake and gradle)
55af553ac Simulation GUI: Map gamepad the same way as DS
c59f9cea5 CameraServer: Add VID/PID support for Linux USB devices (#1960)
3fc89c84d Make splinePointsFromSplines public (#1963)
2c5093797 Fix implicitly deleted move constructors (#1954)
f3ad927f4 Update Java SmartDashboard and LiveWindow to match C++
05c25deb7 Fix move handling of C++ Sendable in SmartDashboard and LiveWindow
d726591ce Fix Gazebo sim plugin build (#1959)
2ff694fa4 Unbreak gradle build when other compilers installed (#1958)
53816155b Improve command decorator names (#1945)
a38f183a9 Fix GenResources.cmake so it's usable in a submodule (#1956)
b3398dca3 Set gradlebase correctly for all examples (#1950)
2c311013d Add Aarch64Bionic platform detection (#1922)
c10f2003c Add generateTrajectory overload (#1944)
63cfa64fb Add getters for pose in odometry classes (#1943)
2402c2bad Fix C++ command group recursive constructor bug (#1941)
f4eedf597 Fix ConcurrentModificationException in CommandScheduler (#1938)
bb0b207d2 Fix array out of bounds exception caused by parallel race group (#1935)
7bd69e591 Fix typo in temperature (#1940)
ec9738245 Bump to 2020 v4 image (#1931)
46303a822 Add messaging to extension loading in the HAL (#1926)
d169d6be9 Set extract_static for Doxygen config so that static members show up (#1930)
4e183eb10 Bump to 2020 v3 image (#1929)
84c185803 LiveWindow: catch errors in callback/builder functions (#1921)
0e3b0f3da Remove deprecated free() calls (#1925)
7f839b87c Remove timeouts from azure builds (#1924)
45b766a5d Fix main thread ID being potentially incorrect for simulation (#1923)
56d782b16 Add secondary camera name for PS3Eye (#1920)
2b4894038 Add simulation GUI plugin
f97d16073 Add imgui build to cmake
55a844a3e HAL sim: Add encoder channel B access
10deba854 Remove sendables from SendableRegistry when close() is called (#1917)
a9f0e4668 Implement sim devices for ADXL345, ADXL362, ADXRS450, Ultrasonic
aa9064586 Add ability to associate other devices with a SimDevice
81c2c8a7d Add simulation generic device/value support
e8d6f8a2c Move mockdata/HAL_Value.h to hal/Value.h
1b266717a Add simulation module support to cmake build (#1906)
fb8f3bd06 Add testbench yaml file (#1915)
846d8def0 Update to 2020 v2 image (#1913)
d6ac6e512 Fix PortForwarder package declaration (#1912)
227157086 Fix PS3Eye exposure setting (#1911)
885744d7e Add myRobot C++ version to cmake build (#1907)
366091fa8 Document that ConditionalCommand requires all subsystems (#1909)
c58b072c8 Fix Drive usage reporting order (#1908)
762c88adb Update compiler versions in readme (#1905)
af8ce568d Add Ramsete unicycle controller (#1790)
b2c2934d0 Fix javadoc warnings about invalid usage of ">" (#1904)
cce26ec78 Replace CRLF line endings with LF (#1902)
cb54602d4 Add support for writing RTR CAN Frames to the CAN API (#1900)
9f740e590 Use OS for serial port instead of NI VISA (#1875)
b23baf611 Add ability to run robot main loop in a separate thread (#1895)
457f94ba2 Add trajectory generation using hermite splines (#1843)
fd612052f Update native utils to use new frchome directory (#1884)
8858ec55c Remove periodic can read call (#1868)
41efb8015 Update CANAPITypes.h (#1860)
c93be1b2d Remove LabVIEW HAL support (#1901)
680f8919e Remove eigen, units and libuv from doxygen generation (#1898)
c5812524f Bump GradleJNI plugin version (#1899)
971303da8 Add PortForwarder class (#1890)
50db77bf2 Fix wpiutil cmake eigen install source directory (#1891)
85d42c199 C++ PIDCommand: Add GetMeasurement() and UseOutput() (#1892)
2dfbb855d wpilibj: Fix SwerveDriveKinematics ctor parameter name (#1889)
471f375a3 Simplify Sendable interface (#1864)
1d8c4d016 Replace ::value and ::type with _v and _t suffixes (#1885)
a5650b943 Add Units Utility class for Java (#1829)
904479ad4 Deprecate GearTooth class for removal (#1878)
86b666bba Add equality comparator to geometry classes (#1882)
62f07c182 Make one-arg Rotation2d constructor implicit (#1883)
f405582f8 Add kinematics suite (#1787)
561cbbd14 Deprecate Filter class for removal (#1876)
84e2973aa Remove unused include from Filesystem.h (#1877)
f49859ebf Remove NI VISA headers, as they are now included in NI Libraries (#1879)
bc59db5e6 Rename DEBUG macro to DEBUG0 (#1871)
dd928b4cb Remove JNI logging (#1872)
3e0f7d099 Use units for new NotifierCommand (#1869)
5ffe15d5f Remove ability to build all combined artifacts (#1867)
516cbef2c  Remove RoboRIO ifdef from simulation headers (#1859)
9b6ffc201 Replace SetOutputRange() with SetIntegratorRange()
ff8b8f0a8 Remove percent tolerance from PID controller
0ca8d667d Clean up AutoCloseable and other Java warnings (#1866)
7112add67 Watchdog: use units::second_t instead of double (#1863)
761bc3ef8 Change C++ WaitCommand to use units (#1865)
1fb301123 Add MathUtils.clamp() for Java (#1861)
eb3e0c9c9 Fix cmake Eigen include directory (#1862)
2250b7fbe Rename GearsBotNew example to GearsBot
c9f9feff1 Replace deprecated API usage in C++ examples
d6b9c7e14 CONTRIBUTING.md: Point to frc-docs instead of screensteps (#1858)
d10a1a797 Fix eigen build in vcpkg (#1856)
2bdb44325 Add frc2 includes to list of "other lib" regexes (#1855)
4b2b21d24 Replace outdated Java collections (#508)
8993ce5bf Move Eigen headers out of main include folder (#1854)
0f532a117 Add PWMSparkMax (#1751)
f7ad363d8 Add jni cross compile options for aarch64 (#1853)
9afea3340 Add support for aarch64 jetson bionic builds (#1844)
d787b5d60 Add more items to .gitignore (#1850)
5dd0d1b7d Use units in SPI
07ac711b3 Fix units deprecated warning in IterativeRobot
decfd858b Correctly report -1 for POV on disconnected joystick (#1852)
076ed7770 Add new C++ Command framework (#1785)
a0be07c37 Refactor HAL handle move construction/assignment (#1845)
558c38308 Add new Java Command framework (#1682)
1379735af Delete RobotState and SensorUtil constructors (#1847)
e3d86fee4 Move circular buffer class from wpilib to wpiutil (#1840)
4cd8a5667 TimedRobot.cpp: Fix deprecation warning (#1846)
b2861f894 Use 2020 artifacts and artifactory server (#1838)
98cc32703 Update to use artifactory to publish artifacts (#1833)
fa0640300 Move drive integration tests into wpilibj/src/test (#1836)
e716c36b8 Fix Nat.java generation to be incremental (#1831)
9fd2b5e3f Fix MSVC builds on cmake windows in vcpkg (#1835)
7e95010a2 Add compile-time EJML matrix wrapper to wpiutil (#1804)
3ebc5a6d3 Add ProfiledPIDController
fc98a79db Clean up PIDController interface in preparation for ProfiledPIDController
fdc098267 Fix compilation error in elevator trapezoid profile example (#1826)
a3dd84e85 Make XBoxController Button enum public (#1823)
a216b9e9e Add TrapezoidProfile example (#1814)
8f386f6bb wpilibc: Add unit-safety to C++ geometry classes (#1811)
c07ac2353 wpilibc: Add overloads for units (#1815)
f1d71da8a Move GetStackTrace and Demangle to wpiutil, add Windows support (#1819)
ef037457e Make LinearFilter copyable and moveable (#1789)
76930250c Remove objective-cpp support (#1816)
1c246418f Move TrapezoidProfileTest to trajectory folder (#1812)
95a54a0f2 Add java arcade drive example (#1810)
a4530243e HAL sim: Fix incorrectly setting dio port to initialized on cleanup (#1813)
09d00a622 Update Java examples to use new PIDController (#1809)
ba9b51742 Add missing Java examples (#841)
6411bd79c InterruptableSensorBase: Fix callback function deletion (#1807)
810e58ea8 I2C: Add tip about writeBulk() to transaction() (#1806)
607d6c148 Fix wpilibj integration tests jar name (#1808)
c9873e81b Remove PIDControllerRunner and mutex from new PIDController (#1795)
98d0706de Fix cscore build with OpenCV 4 (#1803)
fbe67c90c Make Sendable setters synchronous (#1799)
c67a488a0 Format SendableBuilderImpl javadocs (#1802)
8e93ce892 Fix PIDControllerRunner member destruction order (#1801)
c98ca7310 Add EJML dependency to wpiutil (#1769)
3b12276bc SendableBase: remove unnecessary synchronization (#1797)
e6d348f38 Fix missing default name in Java PIDController (#1792)
df12fc2a8 Java cleanups (#1776)
39561751f Update GradleVSCode version (#1786)
37d316aa0 Add C++20 std::math constants shim (#1788)
dd4310959 Deprecate frc/WPILib.h (#1779)
823174f30 Update native utils to 2020.0.4 (#1783)
37c695266 Squelch -Wdeprecated-copy for Eigen with GCC >= 9
04c9b000f Revert "Fix build of Eigen 3.3.7 with GCC 9"
ca3e71e21 wpiutil: Fix Process::Spawn() (#1778)
d946d5a2b Fix Eigen compilation errors and add tests (#1777)
8b1b9ac75 Fix build of Eigen 3.3.7 with GCC 9
2f680ba99 Add Eigen linear algebra library
a885db7d4 Make MotorEncoderTest use LinearFilter (#1775)
ee2410169 Add geometry classes (#1766)
48fe54271 Add HALSIM_SetSendError implementation (#1773)
dff58c87f Fix unused warning in release build (#1771)
dde61aad3 Remove TimerEventHandler typedef from Notifier class (#1767)
0f6ef80ab Add RobotState#IsEStopped and DriverStation#IsEStopped (#952)
e48886187 Move unit tests from integration test suite (#1170)
dffa1a5cb Make null checks more descriptive (#1688)
fe59d854d Notifier: add null check (#1684)
10731f3d6 Update uv Udp wrapper for latest features
89f7b72b6 Update libuv to 1.30.1 release
85f2f8740 wpiutil: Add unique_function (#1761)
73ec94078 Remove SampleRobot (#1658)
62be0392b Replace std::lock_guard and std::lock with std::scoped_lock (#1758)
24d31df55 Make sure move constructor is generated for TrapezoidProfile (#1757)
841ef5d73 Remove template types from lock RAII wrapper usages (#1756)
e582518ba Fix some move constructors (#1754)
8757bc471 Remove pre-C++17 shims (#1752)
ea9512977 Add replacement PIDController class (#1300)
9b798d228 Add TrapezoidProfile class (#1673)
804926fb5 Unconditionally skip athena builds for sim (#1748)
118e9d29d Add C++14 units library (#1749)
c705953d7 Add usage reporting to LinearFilter (#1750)
852d1b9ca Don't cross-build gazebo for raspbian (#1747)
eedb3a1ad Fix GCC 9 warnings (#1730)
60dce66a4 Remove wpi::ArrayRef std::initializer_list constructor (#1745)
9e19b29c3 Use base azure image for primary wpilib build (#1744)
299425071 Update jni library, fix cross builds of the jni symbol check (#1742)
a6b0e9b85 Only disable execution of cross compile google tests (#1741)
3c2093119 Use docker container to run wpiformat (#1740)
5fe2eebce Revert "Don't build halsim_gazebo on raspbian (#1737)" (#1743)
4b1b92bb7 Replace wpi::optional with C++17 std::optional (#1732)
0fbb0d989 Update to 2020 compilers (#1733)
2dc94e605 Disable google tests on cross compilers (#1738)
d9cb57a42 Don't build halsim_gazebo on raspbian (#1737)
f7cfdd7ce Replace crlf line endings with lf (#1731)
b6d5d90d9 Add JaCoCo Support (#1734)
c7ab2baa6 Add way to disable the jni check tasks from a property (#1736)
0c45c5b7e Fix skip athena and skip raspbian flags (#1735)
3dfb01d45 Update to new Native Utils (#1696)
30e936837 Clean up LinearDigitalFilter class (#782)
311e2de4c Remove deprecated Joystick constants (#1715)
c08fd6682 Update CAN manufacturer list (#1706)
258bba0c2 ErrorBase and WPIError improvements (#1727)
372ca4f45 cmake: Enable googletest unit tests (#1720)
223d47af0 HALSIM: support mocking of HAL_SendError() (#1728)
55cb683db Change compiler flags to C++17 (#1723)
ee8a33c56 wpiutil: SafeThread: Add thread id, support getting shared_ptr (#1722)
61426d08d wpiutil: Signal: make operator() const (#1721)
b630b63ef Remove functions in LiveWindow deprecated since 2018 (#1716)
1d0c05d4f Styleguide fixes for #1718 (#1719)
f07569df1 Fix newer GCC/clang compiler warnings (#1718)
0120f3124 C++ SPI: Fix SetClockRate to take int (#1717)
c2829ed98 Configure gradle to ignore unresolved headers (#1711)
221e66f46 Allow disabling static init of JNI libraries (#1672)
738852e11 cmake: Add cross toolchain files for Rio and Pi (#1710)
27b697b08 Remove frc directory include shims (#1714)
9e45373a7 Remove functions and classes deprecated for 2018 season (#1059)
eeb1025ac SPI: Report port as instance for usage reporting (#1704)
bc6f1e246 Windows compiler options improvements (#1709)
bb48ae391 cmake: Move example programs into folders (#1654)
221011494 Update for C++17 and fix MSVC warnings (#1694)
fb1239a2a Add raw sources and sinks to cscore (#1670)
7de947734 Add lambda overloads for interrupts (#1636)
90957aeea Move libuv to its own subfolder in build (#1661)
47aae502a Styleguide fixes (#1702)
0bff98b5e Correct DifferentialDrive::ArcadeDrive param docs (#1698)
b52e40b80 Allow widgets to be added by passing value suppliers (#1690)
4a00cd77b Add usage reporting for the Shuffleboard API (#1685)
e25e515f2  Publish artifacts on azure (#1678)
322ef9b96 Force Java 11, fix javadoc generation (#1695)
d42ef5df0 Fix Watchdog print formatting (#1693)
f432f65be Update copyright year in license to 2019 (#1524)
1726b77ac wpiutil: uv: Remove copy from SimpleBufferPool (#1680)
620bec9ca wpiutil: uv: Add LoopClosing status to Handle (#1647)
7cd6e2e7f UsbCamera: Solve race in windows initialization (#1638)
7732836bd Completely disable watchdog tests on mac (#1679)
698edfda9 Remove framework load, disable mac timeout test (#1676)
1c454b000 Add Shuffleboard calls to IterativeRobotBase in C++ (#1607)
f42905b32 Include missing headers in HAL.h (#1660)
bdc822fad Only generate passthrough URLs for RoboRIO (#1624)
d3affb16b Make failure of HAL_GetFPGATime() more descriptive (#1633)
2de3bf7f5 Update LLVM from stable upstream (#1653)
3cf4f38f5 Fix build on macos10.14.4 (#1648)
4e0c10f48 Fix CAN Clean using wrong ID (#1668)
3b0631324 Fix Gray to BGR conversion in CameraServer (#1665)
6cd1c73ef Fix GUID comparison creating weird symbol (#1659)
063bbab6f MavenArtifacts.md: update links to HTTPS (#1674)
aab4c494d Fix type in build.gradle (#1604)
bf46af260 Disable extraneous data warnings in libjpeg (#1630)
655763a9a Limit length of message sent to DS SendError call (#1618)
a095ec2d8 Fix linker errors with free functions in Threads.h (#1625)
12ab035aa Fix receive side of LabVIEW USB streams (#1621)

Change-Id: Ibd382e1a48925c200850cf90a8121e35c0fcffe3
git-subtree-dir: third_party/allwpilib_2019
git-subtree-split: c36bbcc9a9095489fc078229db4fba3ecd0f9b78
diff --git a/hal/src/main/native/sim/AnalogInput.cpp b/hal/src/main/native/sim/AnalogInput.cpp
index a0f44a7..dc56403 100644
--- a/hal/src/main/native/sim/AnalogInput.cpp
+++ b/hal/src/main/native/sim/AnalogInput.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.                                                               */
@@ -53,6 +53,7 @@
 
   SimAnalogInData[channel].initialized = true;
   SimAnalogInData[channel].accumulatorInitialized = false;
+  SimAnalogInData[channel].simDevice = 0;
 
   return handle;
 }
@@ -71,6 +72,13 @@
   return channel < kNumAnalogInputs && channel >= 0;
 }
 
+void HAL_SetAnalogInputSimDevice(HAL_AnalogInputHandle handle,
+                                 HAL_SimDeviceHandle device) {
+  auto port = analogInputHandles->Get(handle);
+  if (port == nullptr) return;
+  SimAnalogInData[port->channel].simDevice = device;
+}
+
 void HAL_SetAnalogSampleRate(double samplesPerSecond, int32_t* status) {
   // No op
 }
diff --git a/hal/src/main/native/sim/CANAPI.cpp b/hal/src/main/native/sim/CANAPI.cpp
index a54f06f..08b0989 100644
--- a/hal/src/main/native/sim/CANAPI.cpp
+++ b/hal/src/main/native/sim/CANAPI.cpp
@@ -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.                                                               */
@@ -100,12 +100,12 @@
 void HAL_CleanCAN(HAL_CANHandle handle) {
   auto data = canHandles->Free(handle);
 
-  std::lock_guard<wpi::mutex> lock(data->mapMutex);
+  std::scoped_lock lock(data->mapMutex);
 
   for (auto&& i : data->periodicSends) {
     int32_t s = 0;
-    HAL_CAN_SendMessage(i.first, nullptr, 0, HAL_CAN_SEND_PERIOD_STOP_REPEATING,
-                        &s);
+    auto id = CreateCANId(data.get(), i.first);
+    HAL_CAN_SendMessage(id, nullptr, 0, HAL_CAN_SEND_PERIOD_STOP_REPEATING, &s);
     i.second = -1;
   }
 }
@@ -124,7 +124,7 @@
   if (*status != 0) {
     return;
   }
-  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  std::scoped_lock lock(can->mapMutex);
   can->periodicSends[apiId] = -1;
 }
 
@@ -143,10 +143,31 @@
   if (*status != 0) {
     return;
   }
-  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  std::scoped_lock lock(can->mapMutex);
   can->periodicSends[apiId] = repeatMs;
 }
 
+void HAL_WriteCANRTRFrame(HAL_CANHandle handle, int32_t length, int32_t apiId,
+                          int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  auto id = CreateCANId(can.get(), apiId);
+  id |= HAL_CAN_IS_FRAME_REMOTE;
+  uint8_t data[8];
+  std::memset(data, 0, sizeof(data));
+
+  HAL_CAN_SendMessage(id, data, length, HAL_CAN_SEND_PERIOD_NO_REPEAT, status);
+
+  if (*status != 0) {
+    return;
+  }
+  std::scoped_lock lock(can->mapMutex);
+  can->periodicSends[apiId] = -1;
+}
+
 void HAL_StopCANPacketRepeating(HAL_CANHandle handle, int32_t apiId,
                                 int32_t* status) {
   auto can = canHandles->Get(handle);
@@ -162,7 +183,7 @@
   if (*status != 0) {
     return;
   }
-  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  std::scoped_lock lock(can->mapMutex);
   can->periodicSends[apiId] = -1;
 }
 
@@ -181,7 +202,7 @@
   HAL_CAN_ReceiveMessage(&messageId, 0x1FFFFFFF, data, &dataSize, &ts, status);
 
   if (*status == 0) {
-    std::lock_guard<wpi::mutex> lock(can->mapMutex);
+    std::scoped_lock lock(can->mapMutex);
     auto& msg = can->receives[messageId];
     msg.length = dataSize;
     msg.lastTimeStamp = ts;
@@ -206,7 +227,7 @@
   uint32_t ts = 0;
   HAL_CAN_ReceiveMessage(&messageId, 0x1FFFFFFF, data, &dataSize, &ts, status);
 
-  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  std::scoped_lock lock(can->mapMutex);
   if (*status == 0) {
     // fresh update
     auto& msg = can->receives[messageId];
@@ -243,7 +264,7 @@
   uint32_t ts = 0;
   HAL_CAN_ReceiveMessage(&messageId, 0x1FFFFFFF, data, &dataSize, &ts, status);
 
-  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  std::scoped_lock lock(can->mapMutex);
   if (*status == 0) {
     // fresh update
     auto& msg = can->receives[messageId];
@@ -285,7 +306,7 @@
   uint32_t messageId = CreateCANId(can.get(), apiId);
 
   {
-    std::lock_guard<wpi::mutex> lock(can->mapMutex);
+    std::scoped_lock lock(can->mapMutex);
     auto i = can->receives.find(messageId);
     if (i != can->receives.end()) {
       // Found, check if new enough
@@ -305,7 +326,7 @@
   uint32_t ts = 0;
   HAL_CAN_ReceiveMessage(&messageId, 0x1FFFFFFF, data, &dataSize, &ts, status);
 
-  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  std::scoped_lock lock(can->mapMutex);
   if (*status == 0) {
     // fresh update
     auto& msg = can->receives[messageId];
diff --git a/hal/src/main/native/sim/DIO.cpp b/hal/src/main/native/sim/DIO.cpp
index e67b756..2158136 100644
--- a/hal/src/main/native/sim/DIO.cpp
+++ b/hal/src/main/native/sim/DIO.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.                                                               */
@@ -63,8 +63,8 @@
   port->channel = static_cast<uint8_t>(channel);
 
   SimDIOData[channel].initialized = true;
-
   SimDIOData[channel].isInput = input;
+  SimDIOData[channel].simDevice = 0;
 
   return handle;
 }
@@ -78,7 +78,13 @@
   // no status, so no need to check for a proper free.
   digitalChannelHandles->Free(dioPortHandle, HAL_HandleEnum::DIO);
   if (port == nullptr) return;
-  SimDIOData[port->channel].initialized = true;
+  SimDIOData[port->channel].initialized = false;
+}
+
+void HAL_SetDIOSimDevice(HAL_DigitalHandle handle, HAL_SimDeviceHandle device) {
+  auto port = digitalChannelHandles->Get(handle, HAL_HandleEnum::DIO);
+  if (port == nullptr) return;
+  SimDIOData[port->channel].simDevice = device;
 }
 
 HAL_DigitalPWMHandle HAL_AllocateDigitalPWM(int32_t* status) {
diff --git a/hal/src/main/native/sim/DigitalInternal.h b/hal/src/main/native/sim/DigitalInternal.h
index 89644a1..9df4c51 100644
--- a/hal/src/main/native/sim/DigitalInternal.h
+++ b/hal/src/main/native/sim/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.                                                               */
@@ -44,11 +44,11 @@
  * scaling is implemented as an output squelch to get longer periods for old
  * devices.
  */
-constexpr float kDefaultPwmPeriod = 5.05;
+constexpr float kDefaultPwmPeriod = 5.05f;
 /**
  * kDefaultPwmCenter is the PWM range center in ms
  */
-constexpr float kDefaultPwmCenter = 1.5;
+constexpr float kDefaultPwmCenter = 1.5f;
 /**
  * kDefaultPWMStepsDown is the number of PWM steps below the centerpoint
  */
diff --git a/hal/src/main/native/sim/DriverStation.cpp b/hal/src/main/native/sim/DriverStation.cpp
index 0c9c028..a17994e 100644
--- a/hal/src/main/native/sim/DriverStation.cpp
+++ b/hal/src/main/native/sim/DriverStation.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.                                                               */
@@ -28,6 +28,7 @@
 static wpi::mutex newDSDataAvailableMutex;
 static int newDSDataAvailableCounter{0};
 static std::atomic_bool isFinalized{false};
+static std::atomic<HALSIM_SendErrorHandler> sendErrorHandler{nullptr};
 
 namespace hal {
 namespace init {
@@ -41,13 +42,22 @@
 using namespace hal;
 
 extern "C" {
+
+void HALSIM_SetSendError(HALSIM_SendErrorHandler handler) {
+  sendErrorHandler.store(handler);
+}
+
 int32_t HAL_SendError(HAL_Bool isError, int32_t errorCode, HAL_Bool isLVCode,
                       const char* details, const char* location,
                       const char* callStack, HAL_Bool printMsg) {
+  auto errorHandler = sendErrorHandler.load();
+  if (errorHandler)
+    return errorHandler(isError, errorCode, isLVCode, details, location,
+                        callStack, printMsg);
   // Avoid flooding console by keeping track of previous 5 error
   // messages and only printing again if they're longer than 1 second old.
   static constexpr int KEEP_MSGS = 5;
-  std::lock_guard<wpi::mutex> lock(msgMutex);
+  std::scoped_lock lock(msgMutex);
   static std::string prevMsg[KEEP_MSGS];
   static std::chrono::time_point<std::chrono::steady_clock>
       prevMsgTime[KEEP_MSGS];
@@ -219,7 +229,7 @@
   // worth the cycles to check.
   int currentCount = 0;
   {
-    std::unique_lock<wpi::mutex> lock(newDSDataAvailableMutex);
+    std::unique_lock lock(newDSDataAvailableMutex);
     currentCount = newDSDataAvailableCounter;
   }
   if (lastCount == currentCount) return false;
@@ -236,7 +246,7 @@
   auto timeoutTime =
       std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
 
-  std::unique_lock<wpi::mutex> lock(newDSDataAvailableMutex);
+  std::unique_lock lock(newDSDataAvailableMutex);
   int currentCount = newDSDataAvailableCounter;
   while (newDSDataAvailableCounter == currentCount) {
     if (timeout > 0) {
@@ -258,7 +268,7 @@
   // Since we could get other values, require our specific handle
   // to signal our threads
   if (refNum != refNumber) return 0;
-  std::lock_guard<wpi::mutex> lock(newDSDataAvailableMutex);
+  std::scoped_lock lock(newDSDataAvailableMutex);
   // Nofify all threads
   newDSDataAvailableCounter++;
   newDSDataAvailableCond->notify_all();
@@ -272,7 +282,7 @@
   // Initial check, as if it's true initialization has finished
   if (initialized) return;
 
-  std::lock_guard<wpi::mutex> lock(initializeMutex);
+  std::scoped_lock lock(initializeMutex);
   // Second check in case another thread was waiting
   if (initialized) return;
 
diff --git a/hal/src/main/native/sim/Encoder.cpp b/hal/src/main/native/sim/Encoder.cpp
index 3f197a2..36122bf 100644
--- a/hal/src/main/native/sim/Encoder.cpp
+++ b/hal/src/main/native/sim/Encoder.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.                                                               */
@@ -82,8 +82,10 @@
   }
   int16_t index = getHandleIndex(handle);
   SimEncoderData[index].digitalChannelA = getHandleIndex(digitalSourceHandleA);
+  SimEncoderData[index].digitalChannelB = getHandleIndex(digitalSourceHandleB);
   SimEncoderData[index].initialized = true;
   SimEncoderData[index].reverseDirection = reverseDirection;
+  SimEncoderData[index].simDevice = 0;
   // TODO: Add encoding type to Sim data
   encoder->index = index;
   encoder->nativeHandle = nativeHandle;
@@ -104,6 +106,13 @@
   SimEncoderData[encoder->index].initialized = false;
 }
 
+void HAL_SetEncoderSimDevice(HAL_EncoderHandle handle,
+                             HAL_SimDeviceHandle device) {
+  auto encoder = encoderHandles->Get(handle);
+  if (encoder == nullptr) return;
+  SimEncoderData[encoder->index].simDevice = device;
+}
+
 static inline int EncodingScaleFactor(Encoder* encoder) {
   switch (encoder->encodingType) {
     case HAL_Encoder_k1X:
diff --git a/hal/src/main/native/sim/Extensions.cpp b/hal/src/main/native/sim/Extensions.cpp
index 6ef7903..e84c354 100644
--- a/hal/src/main/native/sim/Extensions.cpp
+++ b/hal/src/main/native/sim/Extensions.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.                                                               */
@@ -7,8 +7,10 @@
 
 #include "hal/Extensions.h"
 
+#include <wpi/Path.h>
 #include <wpi/SmallString.h>
 #include <wpi/StringRef.h>
+#include <wpi/raw_ostream.h>
 
 #include "hal/HAL.h"
 
@@ -43,6 +45,9 @@
 
 int HAL_LoadOneExtension(const char* library) {
   int rc = 1;  // It is expected and reasonable not to find an extra simulation
+  wpi::outs() << "HAL Extensions: Attempting to load: "
+              << wpi::sys::path::stem(library) << "\n";
+  wpi::outs().flush();
   HTYPE handle = DLOPEN(library);
 #if !defined(WIN32) && !defined(_WIN32)
   if (!handle) {
@@ -53,17 +58,31 @@
 #else
     libraryName += ".so";
 #endif
+    wpi::outs() << "HAL Extensions: Trying modified name: "
+                << wpi::sys::path::stem(libraryName);
+    wpi::outs().flush();
     handle = DLOPEN(libraryName.c_str());
   }
 #endif
-  if (!handle) return rc;
+  if (!handle) {
+    wpi::outs() << "HAL Extensions: Failed to load library\n";
+    wpi::outs().flush();
+    return rc;
+  }
 
   auto init = reinterpret_cast<halsim_extension_init_func_t*>(
       DLSYM(handle, "HALSIM_InitExtension"));
 
   if (init) rc = (*init)();
 
-  if (rc != 0) DLCLOSE(handle);
+  if (rc != 0) {
+    wpi::outs() << "HAL Extensions: Failed to load extension\n";
+    wpi::outs().flush();
+    DLCLOSE(handle);
+  } else {
+    wpi::outs() << "HAL Extensions: Successfully loaded extension\n";
+    wpi::outs().flush();
+  }
   return rc;
 }
 
@@ -71,7 +90,11 @@
   int rc = 1;
   wpi::SmallVector<wpi::StringRef, 2> libraries;
   const char* e = std::getenv("HALSIM_EXTENSIONS");
-  if (!e) return rc;
+  if (!e) {
+    wpi::outs() << "HAL Extensions: No extensions found\n";
+    wpi::outs().flush();
+    return rc;
+  }
   wpi::StringRef env{e};
   env.split(libraries, DELIM, -1, false);
   for (auto& libref : libraries) {
diff --git a/hal/src/main/native/sim/HAL.cpp b/hal/src/main/native/sim/HAL.cpp
index d058c1a..cf019cf 100644
--- a/hal/src/main/native/sim/HAL.cpp
+++ b/hal/src/main/native/sim/HAL.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.                                                               */
@@ -41,6 +41,7 @@
   InitializePWMData();
   InitializeRelayData();
   InitializeRoboRioData();
+  InitializeSimDeviceData();
   InitializeSPIAccelerometerData();
   InitializeSPIData();
   InitializeAccelerometer();
@@ -60,6 +61,7 @@
   InitializeExtensions();
   InitializeI2C();
   InitializeInterrupts();
+  InitializeMain();
   InitializeMockHooks();
   InitializeNotifier();
   InitializePDP();
@@ -68,6 +70,7 @@
   InitializePWM();
   InitializeRelay();
   InitializeSerialPort();
+  InitializeSimDevice();
   InitializeSolenoid();
   InitializeSPI();
   InitializeThreads();
@@ -231,7 +234,7 @@
   // Initial check, as if it's true initialization has finished
   if (initialized) return true;
 
-  std::lock_guard<wpi::mutex> lock(initializeMutex);
+  std::scoped_lock lock(initializeMutex);
   // Second check in case another thread was waiting
   if (initialized) return true;
 
diff --git a/hal/src/main/native/sim/HALInitializer.h b/hal/src/main/native/sim/HALInitializer.h
index d369a3b..4c91b40 100644
--- a/hal/src/main/native/sim/HALInitializer.h
+++ b/hal/src/main/native/sim/HALInitializer.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.                                                               */
@@ -35,6 +35,7 @@
 extern void InitializePWMData();
 extern void InitializeRelayData();
 extern void InitializeRoboRioData();
+extern void InitializeSimDeviceData();
 extern void InitializeSPIAccelerometerData();
 extern void InitializeSPIData();
 extern void InitializeAccelerometer();
@@ -55,6 +56,7 @@
 extern void InitializeHAL();
 extern void InitializeI2C();
 extern void InitializeInterrupts();
+extern void InitializeMain();
 extern void InitializeMockHooks();
 extern void InitializeNotifier();
 extern void InitializePDP();
@@ -63,6 +65,7 @@
 extern void InitializePWM();
 extern void InitializeRelay();
 extern void InitializeSerialPort();
+extern void InitializeSimDevice();
 extern void InitializeSolenoid();
 extern void InitializeSPI();
 extern void InitializeThreads();
diff --git a/hal/src/main/native/sim/Interrupts.cpp b/hal/src/main/native/sim/Interrupts.cpp
index 75247ca..a7dd285 100644
--- a/hal/src/main/native/sim/Interrupts.cpp
+++ b/hal/src/main/native/sim/Interrupts.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.                                                               */
@@ -19,12 +19,16 @@
 #include "PortsInternal.h"
 #include "hal/AnalogTrigger.h"
 #include "hal/Errors.h"
+#include "hal/Value.h"
 #include "hal/handles/HandlesInternal.h"
 #include "hal/handles/LimitedHandleResource.h"
 #include "hal/handles/UnlimitedHandleResource.h"
 #include "mockdata/AnalogInDataInternal.h"
 #include "mockdata/DIODataInternal.h"
-#include "mockdata/HAL_Value.h"
+
+#ifdef _WIN32
+#pragma warning(disable : 4996 4018 6297 26451 4334)
+#endif
 
 using namespace hal;
 
@@ -54,9 +58,9 @@
 };
 
 struct SynchronousWaitData {
-  HAL_InterruptHandle interruptHandle;
+  HAL_InterruptHandle interruptHandle{HAL_kInvalidHandle};
   wpi::condition_variable waitCond;
-  HAL_Bool waitPredicate;
+  HAL_Bool waitPredicate{false};
 };
 }  // namespace
 
@@ -219,7 +223,7 @@
       std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
 
   {
-    std::unique_lock<wpi::mutex> lock(waitMutex);
+    std::unique_lock lock(waitMutex);
     while (!data->waitPredicate) {
       if (data->waitCond.wait_until(lock, timeoutTime) ==
           std::cv_status::timeout) {
@@ -231,7 +235,7 @@
 
   // Cancel our callback
   SimDIOData[digitalIndex].value.CancelCallback(uid);
-  synchronousInterruptHandles->Free(dataHandle);
+  (void)synchronousInterruptHandles->Free(dataHandle);
 
   // Check for what to return
   if (timedOut) return WaitResult::Timeout;
@@ -283,7 +287,7 @@
       std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
 
   {
-    std::unique_lock<wpi::mutex> lock(waitMutex);
+    std::unique_lock lock(waitMutex);
     while (!data->waitPredicate) {
       if (data->waitCond.wait_until(lock, timeoutTime) ==
           std::cv_status::timeout) {
@@ -295,7 +299,7 @@
 
   // Cancel our callback
   SimAnalogInData[analogIndex].voltage.CancelCallback(uid);
-  synchronousInterruptHandles->Free(dataHandle);
+  (void)synchronousInterruptHandles->Free(dataHandle);
 
   // Check for what to return
   if (timedOut) return WaitResult::Timeout;
diff --git a/hal/src/main/native/sim/Notifier.cpp b/hal/src/main/native/sim/Notifier.cpp
index 9f549d5..579540c 100644
--- a/hal/src/main/native/sim/Notifier.cpp
+++ b/hal/src/main/native/sim/Notifier.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.                                                               */
@@ -38,7 +38,7 @@
   ~NotifierHandleContainer() {
     ForEach([](HAL_NotifierHandle handle, Notifier* notifier) {
       {
-        std::lock_guard<wpi::mutex> lock(notifier->mutex);
+        std::scoped_lock lock(notifier->mutex);
         notifier->active = false;
         notifier->running = false;
       }
@@ -76,7 +76,7 @@
   if (!notifier) return;
 
   {
-    std::lock_guard<wpi::mutex> lock(notifier->mutex);
+    std::scoped_lock lock(notifier->mutex);
     notifier->active = false;
     notifier->running = false;
   }
@@ -89,7 +89,7 @@
 
   // Just in case HAL_StopNotifier() wasn't called...
   {
-    std::lock_guard<wpi::mutex> lock(notifier->mutex);
+    std::scoped_lock lock(notifier->mutex);
     notifier->active = false;
     notifier->running = false;
   }
@@ -102,7 +102,7 @@
   if (!notifier) return;
 
   {
-    std::lock_guard<wpi::mutex> lock(notifier->mutex);
+    std::scoped_lock lock(notifier->mutex);
     notifier->waitTime = triggerTime;
     notifier->running = true;
     notifier->updatedAlarm = true;
@@ -118,7 +118,7 @@
   if (!notifier) return;
 
   {
-    std::lock_guard<wpi::mutex> lock(notifier->mutex);
+    std::scoped_lock lock(notifier->mutex);
     notifier->running = false;
   }
 }
@@ -128,7 +128,7 @@
   auto notifier = notifierHandles->Get(notifierHandle);
   if (!notifier) return 0;
 
-  std::unique_lock<wpi::mutex> lock(notifier->mutex);
+  std::unique_lock lock(notifier->mutex);
   while (notifier->active) {
     double waitTime;
     if (!notifier->running) {
diff --git a/hal/src/main/native/sim/SerialPort.cpp b/hal/src/main/native/sim/SerialPort.cpp
index bc08566..2df2ebe 100644
--- a/hal/src/main/native/sim/SerialPort.cpp
+++ b/hal/src/main/native/sim/SerialPort.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.                                                               */
@@ -16,62 +16,72 @@
 }  // namespace hal
 
 extern "C" {
-void HAL_InitializeSerialPort(HAL_SerialPort port, int32_t* status) {
+HAL_SerialPortHandle HAL_InitializeSerialPort(HAL_SerialPort port,
+                                              int32_t* status) {
   hal::init::CheckInit();
+  return HAL_kInvalidHandle;
 }
 
-void HAL_InitializeSerialPortDirect(HAL_SerialPort port, const char* portName,
-                                    int32_t* status) {}
-
-void HAL_SetSerialBaudRate(HAL_SerialPort port, int32_t baud, int32_t* status) {
+HAL_SerialPortHandle HAL_InitializeSerialPortDirect(HAL_SerialPort port,
+                                                    const char* portName,
+                                                    int32_t* status) {
+  hal::init::CheckInit();
+  return HAL_kInvalidHandle;
 }
 
-void HAL_SetSerialDataBits(HAL_SerialPort port, int32_t bits, int32_t* status) {
-}
+int HAL_GetSerialFD(HAL_SerialPortHandle handle, int32_t* status) { return -1; }
 
-void HAL_SetSerialParity(HAL_SerialPort port, int32_t parity, int32_t* status) {
-}
-
-void HAL_SetSerialStopBits(HAL_SerialPort port, int32_t stopBits,
+void HAL_SetSerialBaudRate(HAL_SerialPortHandle handle, int32_t baud,
                            int32_t* status) {}
 
-void HAL_SetSerialWriteMode(HAL_SerialPort port, int32_t mode,
+void HAL_SetSerialDataBits(HAL_SerialPortHandle handle, int32_t bits,
+                           int32_t* status) {}
+
+void HAL_SetSerialParity(HAL_SerialPortHandle handle, int32_t parity,
+                         int32_t* status) {}
+
+void HAL_SetSerialStopBits(HAL_SerialPortHandle handle, int32_t stopBits,
+                           int32_t* status) {}
+
+void HAL_SetSerialWriteMode(HAL_SerialPortHandle handle, int32_t mode,
                             int32_t* status) {}
 
-void HAL_SetSerialFlowControl(HAL_SerialPort port, int32_t flow,
+void HAL_SetSerialFlowControl(HAL_SerialPortHandle handle, int32_t flow,
                               int32_t* status) {}
 
-void HAL_SetSerialTimeout(HAL_SerialPort port, double timeout,
+void HAL_SetSerialTimeout(HAL_SerialPortHandle handle, double timeout,
                           int32_t* status) {}
 
-void HAL_EnableSerialTermination(HAL_SerialPort port, char terminator,
+void HAL_EnableSerialTermination(HAL_SerialPortHandle handle, char terminator,
                                  int32_t* status) {}
 
-void HAL_DisableSerialTermination(HAL_SerialPort port, int32_t* status) {}
-
-void HAL_SetSerialReadBufferSize(HAL_SerialPort port, int32_t size,
-                                 int32_t* status) {}
-
-void HAL_SetSerialWriteBufferSize(HAL_SerialPort port, int32_t size,
+void HAL_DisableSerialTermination(HAL_SerialPortHandle handle,
                                   int32_t* status) {}
 
-int32_t HAL_GetSerialBytesReceived(HAL_SerialPort port, int32_t* status) {
+void HAL_SetSerialReadBufferSize(HAL_SerialPortHandle handle, int32_t size,
+                                 int32_t* status) {}
+
+void HAL_SetSerialWriteBufferSize(HAL_SerialPortHandle handle, int32_t size,
+                                  int32_t* status) {}
+
+int32_t HAL_GetSerialBytesReceived(HAL_SerialPortHandle handle,
+                                   int32_t* status) {
   return 0;
 }
 
-int32_t HAL_ReadSerial(HAL_SerialPort port, char* buffer, int32_t count,
+int32_t HAL_ReadSerial(HAL_SerialPortHandle handle, char* buffer, int32_t count,
                        int32_t* status) {
   return 0;
 }
 
-int32_t HAL_WriteSerial(HAL_SerialPort port, const char* buffer, int32_t count,
-                        int32_t* status) {
+int32_t HAL_WriteSerial(HAL_SerialPortHandle handle, const char* buffer,
+                        int32_t count, int32_t* status) {
   return 0;
 }
 
-void HAL_FlushSerial(HAL_SerialPort port, int32_t* status) {}
+void HAL_FlushSerial(HAL_SerialPortHandle handle, int32_t* status) {}
 
-void HAL_ClearSerial(HAL_SerialPort port, int32_t* status) {}
+void HAL_ClearSerial(HAL_SerialPortHandle handle, int32_t* status) {}
 
-void HAL_CloseSerial(HAL_SerialPort port, int32_t* status) {}
+void HAL_CloseSerial(HAL_SerialPortHandle handle, int32_t* status) {}
 }  // extern "C"
diff --git a/hal/src/main/native/sim/SimDevice.cpp b/hal/src/main/native/sim/SimDevice.cpp
new file mode 100644
index 0000000..a8f8f80
--- /dev/null
+++ b/hal/src/main/native/sim/SimDevice.cpp
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* 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/SimDevice.h"
+
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "HALInitializer.h"
+#include "mockdata/SimDeviceDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeSimDevice() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_SimDeviceHandle HAL_CreateSimDevice(const char* name) {
+  hal::init::CheckInit();
+  return SimSimDeviceData->CreateDevice(name);
+}
+
+void HAL_FreeSimDevice(HAL_SimDeviceHandle handle) {
+  SimSimDeviceData->FreeDevice(handle);
+}
+
+HAL_SimValueHandle HAL_CreateSimValue(HAL_SimDeviceHandle device,
+                                      const char* name, HAL_Bool readonly,
+                                      const struct HAL_Value* initialValue) {
+  return SimSimDeviceData->CreateValue(device, name, readonly, 0, nullptr,
+                                       *initialValue);
+}
+
+HAL_SimValueHandle HAL_CreateSimValueEnum(HAL_SimDeviceHandle device,
+                                          const char* name, HAL_Bool readonly,
+                                          int32_t numOptions,
+                                          const char** options,
+                                          int32_t initialValue) {
+  return SimSimDeviceData->CreateValue(device, name, readonly, numOptions,
+                                       options, HAL_MakeEnum(initialValue));
+}
+
+void HAL_GetSimValue(HAL_SimValueHandle handle, struct HAL_Value* value) {
+  *value = SimSimDeviceData->GetValue(handle);
+}
+
+void HAL_SetSimValue(HAL_SimValueHandle handle, const struct HAL_Value* value) {
+  SimSimDeviceData->SetValue(handle, *value);
+}
+
+hal::SimDevice::SimDevice(const char* name, int index) {
+  wpi::SmallString<128> fullname;
+  wpi::raw_svector_ostream os(fullname);
+  os << name << '[' << index << ']';
+
+  m_handle = HAL_CreateSimDevice(fullname.c_str());
+}
+
+hal::SimDevice::SimDevice(const char* name, int index, int channel) {
+  wpi::SmallString<128> fullname;
+  wpi::raw_svector_ostream os(fullname);
+  os << name << '[' << index << ',' << channel << ']';
+
+  m_handle = HAL_CreateSimDevice(fullname.c_str());
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/sim/jni/BufferCallbackStore.cpp b/hal/src/main/native/sim/jni/BufferCallbackStore.cpp
index fbf3adc..3c9941e 100644
--- a/hal/src/main/native/sim/jni/BufferCallbackStore.cpp
+++ b/hal/src/main/native/sim/jni/BufferCallbackStore.cpp
@@ -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,8 +13,8 @@
 
 #include "SimulatorJNI.h"
 #include "hal/Types.h"
+#include "hal/Value.h"
 #include "hal/handles/UnlimitedHandleResource.h"
-#include "mockdata/HAL_Value.h"
 #include "mockdata/NotifyListener.h"
 
 using namespace wpi::java;
diff --git a/hal/src/main/native/sim/jni/BufferCallbackStore.h b/hal/src/main/native/sim/jni/BufferCallbackStore.h
index b9d49ac..6b472ac 100644
--- a/hal/src/main/native/sim/jni/BufferCallbackStore.h
+++ b/hal/src/main/native/sim/jni/BufferCallbackStore.h
@@ -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,8 +13,8 @@
 
 #include "SimulatorJNI.h"
 #include "hal/Types.h"
+#include "hal/Value.h"
 #include "hal/handles/UnlimitedHandleResource.h"
-#include "mockdata/HAL_Value.h"
 #include "mockdata/NotifyListener.h"
 
 namespace sim {
diff --git a/hal/src/main/native/sim/jni/CallbackStore.cpp b/hal/src/main/native/sim/jni/CallbackStore.cpp
index abef9b0..318ab1e 100644
--- a/hal/src/main/native/sim/jni/CallbackStore.cpp
+++ b/hal/src/main/native/sim/jni/CallbackStore.cpp
@@ -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,8 +13,8 @@
 
 #include "SimulatorJNI.h"
 #include "hal/Types.h"
+#include "hal/Value.h"
 #include "hal/handles/UnlimitedHandleResource.h"
-#include "mockdata/HAL_Value.h"
 #include "mockdata/NotifyListener.h"
 
 using namespace wpi::java;
diff --git a/hal/src/main/native/sim/jni/CallbackStore.h b/hal/src/main/native/sim/jni/CallbackStore.h
index 94454b0..eacf314 100644
--- a/hal/src/main/native/sim/jni/CallbackStore.h
+++ b/hal/src/main/native/sim/jni/CallbackStore.h
@@ -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,8 +13,8 @@
 
 #include "SimulatorJNI.h"
 #include "hal/Types.h"
+#include "hal/Value.h"
 #include "hal/handles/UnlimitedHandleResource.h"
-#include "mockdata/HAL_Value.h"
 #include "mockdata/NotifyListener.h"
 
 namespace sim {
diff --git a/hal/src/main/native/sim/jni/ConstBufferCallbackStore.cpp b/hal/src/main/native/sim/jni/ConstBufferCallbackStore.cpp
index 781725b..d681983 100644
--- a/hal/src/main/native/sim/jni/ConstBufferCallbackStore.cpp
+++ b/hal/src/main/native/sim/jni/ConstBufferCallbackStore.cpp
@@ -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,8 +13,8 @@
 
 #include "SimulatorJNI.h"
 #include "hal/Types.h"
+#include "hal/Value.h"
 #include "hal/handles/UnlimitedHandleResource.h"
-#include "mockdata/HAL_Value.h"
 #include "mockdata/NotifyListener.h"
 
 using namespace wpi::java;
diff --git a/hal/src/main/native/sim/jni/ConstBufferCallbackStore.h b/hal/src/main/native/sim/jni/ConstBufferCallbackStore.h
index 1b0f54e..2164a74 100644
--- a/hal/src/main/native/sim/jni/ConstBufferCallbackStore.h
+++ b/hal/src/main/native/sim/jni/ConstBufferCallbackStore.h
@@ -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,8 +13,8 @@
 
 #include "SimulatorJNI.h"
 #include "hal/Types.h"
+#include "hal/Value.h"
 #include "hal/handles/UnlimitedHandleResource.h"
-#include "mockdata/HAL_Value.h"
 #include "mockdata/NotifyListener.h"
 
 namespace sim {
diff --git a/hal/src/main/native/sim/jni/SimDeviceDataJNI.cpp b/hal/src/main/native/sim/jni/SimDeviceDataJNI.cpp
new file mode 100644
index 0000000..f6cd05e
--- /dev/null
+++ b/hal/src/main/native/sim/jni/SimDeviceDataJNI.cpp
@@ -0,0 +1,573 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SimDeviceDataJNI.h"
+
+#include <jni.h>
+
+#include <functional>
+#include <string>
+#include <utility>
+
+#include <wpi/UidVector.h>
+#include <wpi/jni_util.h>
+
+#include "SimulatorJNI.h"
+#include "edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI.h"
+#include "mockdata/SimDeviceData.h"
+
+using namespace wpi::java;
+
+static JClass simDeviceInfoCls;
+static JClass simValueInfoCls;
+static JClass simDeviceCallbackCls;
+static JClass simValueCallbackCls;
+static jmethodID simDeviceCallbackCallback;
+static jmethodID simValueCallbackCallback;
+
+namespace {
+
+struct DeviceInfo {
+  DeviceInfo(const char* name_, HAL_SimDeviceHandle handle_)
+      : name{name_}, handle{handle_} {}
+  std::string name;
+  HAL_SimValueHandle handle;
+
+  jobject MakeJava(JNIEnv* env) const;
+  void CallJava(JNIEnv* env, jobject callobj) const;
+};
+
+struct ValueInfo {
+  ValueInfo(const char* name_, HAL_SimValueHandle handle_, bool readonly_,
+            const HAL_Value& value_)
+      : name{name_}, handle{handle_}, readonly{readonly_}, value{value_} {}
+  std::string name;
+  HAL_SimValueHandle handle;
+  bool readonly;
+  HAL_Value value;
+
+  jobject MakeJava(JNIEnv* env) const;
+  void CallJava(JNIEnv* env, jobject callobj) const;
+
+ private:
+  std::pair<jlong, jdouble> ToValue12() const;
+};
+
+}  // namespace
+
+jobject DeviceInfo::MakeJava(JNIEnv* env) const {
+  static jmethodID func =
+      env->GetMethodID(simDeviceInfoCls, "<init>", "(Ljava/lang/String;I)V");
+  return env->NewObject(simDeviceInfoCls, func, MakeJString(env, name),
+                        (jint)handle);
+}
+
+void DeviceInfo::CallJava(JNIEnv* env, jobject callobj) const {
+  env->CallVoidMethod(callobj, simDeviceCallbackCallback,
+                      MakeJString(env, name), (jint)handle);
+}
+
+std::pair<jlong, jdouble> ValueInfo::ToValue12() const {
+  jlong value1 = 0;
+  jdouble value2 = 0.0;
+  switch (value.type) {
+    case HAL_BOOLEAN:
+      value1 = value.data.v_boolean;
+      break;
+    case HAL_DOUBLE:
+      value2 = value.data.v_double;
+      break;
+    case HAL_ENUM:
+      value1 = value.data.v_enum;
+      break;
+    case HAL_INT:
+      value1 = value.data.v_int;
+      break;
+    case HAL_LONG:
+      value1 = value.data.v_long;
+      break;
+    default:
+      break;
+  }
+  return std::pair(value1, value2);
+}
+
+jobject ValueInfo::MakeJava(JNIEnv* env) const {
+  static jmethodID func =
+      env->GetMethodID(simValueInfoCls, "<init>", "(Ljava/lang/String;IZIJD)V");
+  auto [value1, value2] = ToValue12();
+  return env->NewObject(simValueInfoCls, func, MakeJString(env, name),
+                        (jint)handle, (jboolean)readonly, (jint)value.type,
+                        value1, value2);
+}
+
+void ValueInfo::CallJava(JNIEnv* env, jobject callobj) const {
+  auto [value1, value2] = ToValue12();
+  env->CallVoidMethod(callobj, simValueCallbackCallback, MakeJString(env, name),
+                      (jint)handle, (jboolean)readonly, (jint)value.type,
+                      value1, value2);
+}
+
+namespace {
+
+class CallbackStore {
+ public:
+  explicit CallbackStore(JNIEnv* env, jobject obj) : m_call{env, obj} {}
+  ~CallbackStore() {
+    if (m_cancelCallback) m_cancelCallback();
+  }
+
+  void SetCancel(std::function<void()> cancelCallback) {
+    m_cancelCallback = std::move(cancelCallback);
+  }
+  void Free(JNIEnv* env) { m_call.free(env); }
+  jobject Get() const { return m_call; }
+
+ private:
+  wpi::java::JGlobal<jobject> m_call;
+  std::function<void()> m_cancelCallback;
+};
+
+class CallbackThreadJNI : public wpi::SafeThread {
+ public:
+  void Main();
+
+  using DeviceCalls =
+      std::vector<std::pair<std::weak_ptr<CallbackStore>, DeviceInfo>>;
+  DeviceCalls m_deviceCalls;
+  using ValueCalls =
+      std::vector<std::pair<std::weak_ptr<CallbackStore>, ValueInfo>>;
+  ValueCalls m_valueCalls;
+
+  wpi::UidVector<std::shared_ptr<CallbackStore>, 4> m_callbacks;
+};
+
+class CallbackJNI {
+ public:
+  static CallbackJNI& GetInstance() {
+    static CallbackJNI inst;
+    return inst;
+  }
+  void SendDevice(int32_t callback, DeviceInfo info);
+  void SendValue(int32_t callback, ValueInfo info);
+
+  std::pair<int32_t, std::shared_ptr<CallbackStore>> AllocateCallback(
+      JNIEnv* env, jobject obj);
+
+  void FreeCallback(JNIEnv* env, int32_t uid);
+
+ private:
+  CallbackJNI() { m_owner.Start(); }
+
+  wpi::SafeThreadOwner<CallbackThreadJNI> m_owner;
+};
+
+}  // namespace
+
+void CallbackThreadJNI::Main() {
+  JNIEnv* env;
+  JavaVMAttachArgs args;
+  args.version = JNI_VERSION_1_2;
+  args.name = const_cast<char*>("SimDeviceCallback");
+  args.group = nullptr;
+  jint rs = sim::GetJVM()->AttachCurrentThreadAsDaemon(
+      reinterpret_cast<void**>(&env), &args);
+  if (rs != JNI_OK) return;
+
+  DeviceCalls deviceCalls;
+  ValueCalls valueCalls;
+
+  std::unique_lock lock(m_mutex);
+  while (m_active) {
+    m_cond.wait(lock, [&] { return !m_active; });
+    if (!m_active) break;
+
+    deviceCalls.swap(m_deviceCalls);
+    valueCalls.swap(m_valueCalls);
+
+    lock.unlock();  // don't hold mutex during callback execution
+
+    for (auto&& call : deviceCalls) {
+      if (auto store = call.first.lock()) {
+        if (jobject callobj = store->Get()) {
+          call.second.CallJava(env, callobj);
+          if (env->ExceptionCheck()) {
+            env->ExceptionDescribe();
+            env->ExceptionClear();
+          }
+        }
+      }
+    }
+
+    for (auto&& call : valueCalls) {
+      if (auto store = call.first.lock()) {
+        if (jobject callobj = store->Get()) {
+          call.second.CallJava(env, callobj);
+          if (env->ExceptionCheck()) {
+            env->ExceptionDescribe();
+            env->ExceptionClear();
+          }
+        }
+      }
+    }
+
+    deviceCalls.clear();
+    valueCalls.clear();
+
+    lock.lock();
+  }
+
+  // free global references
+  for (auto&& callback : m_callbacks) callback->Free(env);
+
+  sim::GetJVM()->DetachCurrentThread();
+}
+
+void CallbackJNI::SendDevice(int32_t callback, DeviceInfo info) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+  thr->m_deviceCalls.emplace_back(thr->m_callbacks[callback], std::move(info));
+  thr->m_cond.notify_one();
+}
+
+void CallbackJNI::SendValue(int32_t callback, ValueInfo info) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+  thr->m_valueCalls.emplace_back(thr->m_callbacks[callback], std::move(info));
+  thr->m_cond.notify_one();
+}
+
+std::pair<int32_t, std::shared_ptr<CallbackStore>>
+CallbackJNI::AllocateCallback(JNIEnv* env, jobject obj) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return std::pair(0, nullptr);
+  auto store = std::make_shared<CallbackStore>(env, obj);
+  return std::pair(thr->m_callbacks.emplace_back(store) + 1, store);
+}
+
+void CallbackJNI::FreeCallback(JNIEnv* env, int32_t uid) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+  if (uid <= 0 || static_cast<uint32_t>(uid) >= thr->m_callbacks.size()) return;
+  --uid;
+  auto store = std::move(thr->m_callbacks[uid]);
+  thr->m_callbacks.erase(uid);
+  store->Free(env);
+}
+
+namespace sim {
+
+bool InitializeSimDeviceDataJNI(JNIEnv* env) {
+  simDeviceInfoCls = JClass(
+      env, "edu/wpi/first/hal/sim/mockdata/SimDeviceDataJNI$SimDeviceInfo");
+  if (!simDeviceInfoCls) return false;
+
+  simValueInfoCls = JClass(
+      env, "edu/wpi/first/hal/sim/mockdata/SimDeviceDataJNI$SimValueInfo");
+  if (!simValueInfoCls) return false;
+
+  simDeviceCallbackCls = JClass(env, "edu/wpi/first/hal/sim/SimDeviceCallback");
+  if (!simDeviceCallbackCls) return false;
+
+  simDeviceCallbackCallback = env->GetMethodID(simDeviceCallbackCls, "callback",
+                                               "(Ljava/lang/String;I)V");
+  if (!simDeviceCallbackCallback) return false;
+
+  simValueCallbackCls = JClass(env, "edu/wpi/first/hal/sim/SimValueCallback");
+  if (!simValueCallbackCls) return false;
+
+  simValueCallbackCallback = env->GetMethodID(
+      simValueCallbackCls, "callbackNative", "(Ljava/lang/String;IZIJD)V");
+  if (!simValueCallbackCallback) return false;
+
+  return true;
+}
+
+void FreeSimDeviceDataJNI(JNIEnv* env) {
+  simDeviceInfoCls.free(env);
+  simValueInfoCls.free(env);
+  simDeviceCallbackCls.free(env);
+  simValueCallbackCls.free(env);
+}
+
+}  // namespace sim
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    registerSimDeviceCreatedCallback
+ * Signature: (Ljava/lang/String;Ljava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_registerSimDeviceCreatedCallback
+  (JNIEnv* env, jclass, jstring prefix, jobject callback,
+   jboolean initialNotify)
+{
+  auto [uid, store] =
+      CallbackJNI::GetInstance().AllocateCallback(env, callback);
+  int32_t cuid = HALSIM_RegisterSimDeviceCreatedCallback(
+      JStringRef{env, prefix}.c_str(),
+      reinterpret_cast<void*>(static_cast<intptr_t>(uid)),
+      [](const char* name, void* param, HAL_SimDeviceHandle handle) {
+        int32_t uid = reinterpret_cast<intptr_t>(param);
+        CallbackJNI::GetInstance().SendDevice(uid, DeviceInfo{name, handle});
+      },
+      initialNotify);
+  store->SetCancel([cuid] { HALSIM_CancelSimDeviceCreatedCallback(cuid); });
+  return uid;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    cancelSimDeviceCreatedCallback
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_cancelSimDeviceCreatedCallback
+  (JNIEnv* env, jclass, jint uid)
+{
+  CallbackJNI::GetInstance().FreeCallback(env, uid);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    registerSimDeviceFreedCallback
+ * Signature: (Ljava/lang/String;Ljava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_registerSimDeviceFreedCallback
+  (JNIEnv* env, jclass, jstring prefix, jobject callback)
+{
+  auto [uid, store] =
+      CallbackJNI::GetInstance().AllocateCallback(env, callback);
+  int32_t cuid = HALSIM_RegisterSimDeviceFreedCallback(
+      JStringRef{env, prefix}.c_str(),
+      reinterpret_cast<void*>(static_cast<intptr_t>(uid)),
+      [](const char* name, void* param, HAL_SimDeviceHandle handle) {
+        int32_t uid = reinterpret_cast<intptr_t>(param);
+        CallbackJNI::GetInstance().SendDevice(uid, DeviceInfo{name, handle});
+      });
+  store->SetCancel([cuid] { HALSIM_CancelSimDeviceFreedCallback(cuid); });
+  return uid;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    cancelSimDeviceFreedCallback
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_cancelSimDeviceFreedCallback
+  (JNIEnv* env, jclass, jint uid)
+{
+  CallbackJNI::GetInstance().FreeCallback(env, uid);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    getSimDeviceHandle
+ * Signature: (Ljava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_getSimDeviceHandle
+  (JNIEnv* env, jclass, jstring name)
+{
+  return HALSIM_GetSimDeviceHandle(JStringRef{env, name}.c_str());
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    getSimValueDeviceHandle
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_getSimValueDeviceHandle
+  (JNIEnv*, jclass, jint handle)
+{
+  return HALSIM_GetSimValueDeviceHandle(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    enumerateSimDevices
+ * Signature: (Ljava/lang/String;)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_enumerateSimDevices
+  (JNIEnv* env, jclass, jstring prefix)
+{
+  // get values
+  std::vector<DeviceInfo> arr;
+  HALSIM_EnumerateSimDevices(
+      JStringRef{env, prefix}.c_str(), &arr,
+      [](const char* name, void* param, HAL_SimDeviceHandle handle) {
+        auto arr = static_cast<std::vector<DeviceInfo>*>(param);
+        arr->emplace_back(name, handle);
+      });
+
+  // convert to java
+  size_t numElems = arr.size();
+  jobjectArray jarr =
+      env->NewObjectArray(arr.size(), simDeviceInfoCls, nullptr);
+  if (!jarr) return nullptr;
+  for (size_t i = 0; i < numElems; ++i) {
+    JLocal<jobject> elem{env, arr[i].MakeJava(env)};
+    env->SetObjectArrayElement(jarr, i, elem.obj());
+  }
+  return jarr;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    registerSimValueCreatedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_registerSimValueCreatedCallback
+  (JNIEnv* env, jclass, jint device, jobject callback, jboolean initialNotify)
+{
+  auto [uid, store] =
+      CallbackJNI::GetInstance().AllocateCallback(env, callback);
+  int32_t cuid = HALSIM_RegisterSimValueCreatedCallback(
+      device, reinterpret_cast<void*>(static_cast<intptr_t>(uid)),
+      [](const char* name, void* param, HAL_SimValueHandle handle,
+         HAL_Bool readonly, const HAL_Value* value) {
+        int32_t uid = reinterpret_cast<intptr_t>(param);
+        CallbackJNI::GetInstance().SendValue(
+            uid, ValueInfo{name, handle, static_cast<bool>(readonly), *value});
+      },
+      initialNotify);
+  store->SetCancel([cuid] { HALSIM_CancelSimValueCreatedCallback(cuid); });
+  return uid;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    cancelSimValueCreatedCallback
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_cancelSimValueCreatedCallback
+  (JNIEnv* env, jclass, jint uid)
+{
+  CallbackJNI::GetInstance().FreeCallback(env, uid);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    registerSimValueChangedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_registerSimValueChangedCallback
+  (JNIEnv* env, jclass, jint handle, jobject callback, jboolean initialNotify)
+{
+  auto [uid, store] =
+      CallbackJNI::GetInstance().AllocateCallback(env, callback);
+  int32_t cuid = HALSIM_RegisterSimValueChangedCallback(
+      handle, reinterpret_cast<void*>(static_cast<intptr_t>(uid)),
+      [](const char* name, void* param, HAL_SimValueHandle handle,
+         HAL_Bool readonly, const HAL_Value* value) {
+        int32_t uid = reinterpret_cast<intptr_t>(param);
+        CallbackJNI::GetInstance().SendValue(
+            uid, ValueInfo{name, handle, static_cast<bool>(readonly), *value});
+      },
+      initialNotify);
+  store->SetCancel([cuid] { HALSIM_CancelSimValueChangedCallback(cuid); });
+  return uid;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    cancelSimValueChangedCallback
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_cancelSimValueChangedCallback
+  (JNIEnv* env, jclass, jint uid)
+{
+  CallbackJNI::GetInstance().FreeCallback(env, uid);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    getSimValueHandle
+ * Signature: (ILjava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_getSimValueHandle
+  (JNIEnv* env, jclass, jint device, jstring name)
+{
+  return HALSIM_GetSimValueHandle(device, JStringRef{env, name}.c_str());
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    enumerateSimValues
+ * Signature: (I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_enumerateSimValues
+  (JNIEnv* env, jclass, jint device)
+{
+  // get values
+  std::vector<ValueInfo> arr;
+  HALSIM_EnumerateSimValues(
+      device, &arr,
+      [](const char* name, void* param, HAL_SimValueHandle handle,
+         HAL_Bool readonly, const HAL_Value* value) {
+        auto arr = static_cast<std::vector<ValueInfo>*>(param);
+        arr->emplace_back(name, handle, readonly, *value);
+      });
+
+  // convert to java
+  size_t numElems = arr.size();
+  jobjectArray jarr = env->NewObjectArray(arr.size(), simValueInfoCls, nullptr);
+  if (!jarr) return nullptr;
+  for (size_t i = 0; i < numElems; ++i) {
+    JLocal<jobject> elem{env, arr[i].MakeJava(env)};
+    env->SetObjectArrayElement(jarr, i, elem.obj());
+  }
+  return jarr;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    getSimValueEnumOptions
+ * Signature: (I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_getSimValueEnumOptions
+  (JNIEnv* env, jclass, jint handle)
+{
+  static JClass stringCls{env, "java/lang/String"};
+  if (!stringCls) return nullptr;
+  int32_t numElems = 0;
+  const char** elems = HALSIM_GetSimValueEnumOptions(handle, &numElems);
+  jobjectArray jarr = env->NewObjectArray(numElems, stringCls, nullptr);
+  if (!jarr) return nullptr;
+  for (int32_t i = 0; i < numElems; ++i) {
+    JLocal<jstring> elem{env, MakeJString(env, elems[i])};
+    env->SetObjectArrayElement(jarr, i, elem.obj());
+  }
+  return jarr;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI
+ * Method:    resetSimDeviceData
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimDeviceDataJNI_resetSimDeviceData
+  (JNIEnv*, jclass)
+{
+  HALSIM_ResetSimDeviceData();
+}
+
+}  // extern "C"
diff --git a/hal/src/main/native/sim/jni/SimDeviceDataJNI.h b/hal/src/main/native/sim/jni/SimDeviceDataJNI.h
new file mode 100644
index 0000000..56f6d9b
--- /dev/null
+++ b/hal/src/main/native/sim/jni/SimDeviceDataJNI.h
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <jni.h>
+
+namespace sim {
+bool InitializeSimDeviceDataJNI(JNIEnv* env);
+void FreeSimDeviceDataJNI(JNIEnv* env);
+}  // namespace sim
diff --git a/hal/src/main/native/sim/jni/SimulatorJNI.cpp b/hal/src/main/native/sim/jni/SimulatorJNI.cpp
index d1e0f7d..bba8f01 100644
--- a/hal/src/main/native/sim/jni/SimulatorJNI.cpp
+++ b/hal/src/main/native/sim/jni/SimulatorJNI.cpp
@@ -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.                                                               */
@@ -7,20 +7,21 @@
 
 #include "SimulatorJNI.h"
 
+#include <wpi/jni_util.h>
+
 #include "BufferCallbackStore.h"
 #include "CallbackStore.h"
 #include "ConstBufferCallbackStore.h"
+#include "SimDeviceDataJNI.h"
 #include "SpiReadAutoReceiveBufferCallbackStore.h"
 #include "edu_wpi_first_hal_sim_mockdata_SimulatorJNI.h"
 #include "hal/HAL.h"
-#include "hal/cpp/Log.h"
 #include "hal/handles/HandlesInternal.h"
 #include "mockdata/MockHooks.h"
 
 using namespace wpi::java;
 
 static JavaVM* jvm = nullptr;
-static JClass simValueCls;
 static JClass notifyCallbackCls;
 static JClass bufferCallbackCls;
 static JClass constBufferCallbackCls;
@@ -38,9 +39,6 @@
   if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK)
     return JNI_ERR;
 
-  simValueCls = JClass(env, "edu/wpi/first/hal/sim/SimValue");
-  if (!simValueCls) return JNI_ERR;
-
   notifyCallbackCls = JClass(env, "edu/wpi/first/hal/sim/NotifyCallback");
   if (!notifyCallbackCls) return JNI_ERR;
 
@@ -76,6 +74,7 @@
   InitializeBufferStore();
   InitializeConstBufferStore();
   InitializeSpiBufferStore();
+  if (!InitializeSimDeviceDataJNI(env)) return JNI_ERR;
 
   return JNI_VERSION_1_6;
 }
@@ -85,11 +84,11 @@
   if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK)
     return;
 
-  simValueCls.free(env);
   notifyCallbackCls.free(env);
   bufferCallbackCls.free(env);
   constBufferCallbackCls.free(env);
   spiReadAutoReceiveBufferCallbackCls.free(env);
+  FreeSimDeviceDataJNI(env);
   jvm = nullptr;
 }
 
diff --git a/hal/src/main/native/sim/jni/SimulatorJNI.h b/hal/src/main/native/sim/jni/SimulatorJNI.h
index 60d0ca3..8680396 100644
--- a/hal/src/main/native/sim/jni/SimulatorJNI.h
+++ b/hal/src/main/native/sim/jni/SimulatorJNI.h
@@ -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.                                                               */
@@ -7,11 +7,8 @@
 
 #pragma once
 
-#include <wpi/jni_util.h>
-
 #include "hal/Types.h"
 #include "jni.h"
-#include "mockdata/HAL_Value.h"
 
 typedef HAL_Handle SIM_JniHandle;
 
diff --git a/hal/src/main/native/sim/jni/SpiReadAutoReceiveBufferCallbackStore.cpp b/hal/src/main/native/sim/jni/SpiReadAutoReceiveBufferCallbackStore.cpp
index 935c8bf..b75bb1e 100644
--- a/hal/src/main/native/sim/jni/SpiReadAutoReceiveBufferCallbackStore.cpp
+++ b/hal/src/main/native/sim/jni/SpiReadAutoReceiveBufferCallbackStore.cpp
@@ -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,8 +13,8 @@
 
 #include "SimulatorJNI.h"
 #include "hal/Types.h"
+#include "hal/Value.h"
 #include "hal/handles/UnlimitedHandleResource.h"
-#include "mockdata/HAL_Value.h"
 #include "mockdata/NotifyListener.h"
 
 using namespace wpi::java;
diff --git a/hal/src/main/native/sim/jni/SpiReadAutoReceiveBufferCallbackStore.h b/hal/src/main/native/sim/jni/SpiReadAutoReceiveBufferCallbackStore.h
index 643a874..1a03f59 100644
--- a/hal/src/main/native/sim/jni/SpiReadAutoReceiveBufferCallbackStore.h
+++ b/hal/src/main/native/sim/jni/SpiReadAutoReceiveBufferCallbackStore.h
@@ -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,8 +13,8 @@
 
 #include "SimulatorJNI.h"
 #include "hal/Types.h"
+#include "hal/Value.h"
 #include "hal/handles/UnlimitedHandleResource.h"
-#include "mockdata/HAL_Value.h"
 #include "mockdata/NotifyListener.h"
 #include "mockdata/SPIData.h"
 
diff --git a/hal/src/main/native/sim/mockdata/AccelerometerDataInternal.h b/hal/src/main/native/sim/mockdata/AccelerometerDataInternal.h
index 15e55ac..9db0875 100644
--- a/hal/src/main/native/sim/mockdata/AccelerometerDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/AccelerometerDataInternal.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.                                                               */
@@ -19,16 +19,16 @@
   HAL_SIMDATAVALUE_DEFINE_NAME(Z)
 
   static inline HAL_Value MakeRangeValue(HAL_AccelerometerRange value) {
-    return MakeEnum(value);
+    return HAL_MakeEnum(value);
   }
 
  public:
-  SimDataValue<HAL_Bool, MakeBoolean, GetActiveName> active{false};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetActiveName> active{false};
   SimDataValue<HAL_AccelerometerRange, MakeRangeValue, GetRangeName> range{
       static_cast<HAL_AccelerometerRange>(0)};
-  SimDataValue<double, MakeDouble, GetXName> x{0.0};
-  SimDataValue<double, MakeDouble, GetYName> y{0.0};
-  SimDataValue<double, MakeDouble, GetZName> z{0.0};
+  SimDataValue<double, HAL_MakeDouble, GetXName> x{0.0};
+  SimDataValue<double, HAL_MakeDouble, GetYName> y{0.0};
+  SimDataValue<double, HAL_MakeDouble, GetZName> z{0.0};
 
   virtual void ResetData();
 };
diff --git a/hal/src/main/native/sim/mockdata/AnalogGyroDataInternal.h b/hal/src/main/native/sim/mockdata/AnalogGyroDataInternal.h
index 8dfcb52..427d2fb 100644
--- a/hal/src/main/native/sim/mockdata/AnalogGyroDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/AnalogGyroDataInternal.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.                                                               */
@@ -17,9 +17,10 @@
   HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
 
  public:
-  SimDataValue<double, MakeDouble, GetAngleName> angle{0.0};
-  SimDataValue<double, MakeDouble, GetRateName> rate{0.0};
-  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
+  SimDataValue<double, HAL_MakeDouble, GetAngleName> angle{0.0};
+  SimDataValue<double, HAL_MakeDouble, GetRateName> rate{0.0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{
+      false};
 
   virtual void ResetData();
 };
diff --git a/hal/src/main/native/sim/mockdata/AnalogInData.cpp b/hal/src/main/native/sim/mockdata/AnalogInData.cpp
index 1efdf50..a2a871c 100644
--- a/hal/src/main/native/sim/mockdata/AnalogInData.cpp
+++ b/hal/src/main/native/sim/mockdata/AnalogInData.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.                                                               */
@@ -22,6 +22,7 @@
 AnalogInData* hal::SimAnalogInData;
 void AnalogInData::ResetData() {
   initialized.Reset(false);
+  simDevice = 0;
   averageBits.Reset(7);
   oversampleBits.Reset(0);
   voltage.Reset(0.0);
@@ -37,6 +38,10 @@
   SimAnalogInData[index].ResetData();
 }
 
+HAL_SimDeviceHandle HALSIM_GetAnalogInSimDevice(int32_t index) {
+  return SimAnalogInData[index].simDevice;
+}
+
 #define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                   \
   HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, AnalogIn##CAPINAME, \
                                SimAnalogInData, LOWERNAME)
diff --git a/hal/src/main/native/sim/mockdata/AnalogInDataInternal.h b/hal/src/main/native/sim/mockdata/AnalogInDataInternal.h
index 94121ca..cd8348d 100644
--- a/hal/src/main/native/sim/mockdata/AnalogInDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/AnalogInDataInternal.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.                                                               */
@@ -23,16 +23,21 @@
   HAL_SIMDATAVALUE_DEFINE_NAME(AccumulatorDeadband)
 
  public:
-  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
-  SimDataValue<int32_t, MakeInt, GetAverageBitsName> averageBits{7};
-  SimDataValue<int32_t, MakeInt, GetOversampleBitsName> oversampleBits{0};
-  SimDataValue<double, MakeDouble, GetVoltageName> voltage{0.0};
-  SimDataValue<HAL_Bool, MakeBoolean, GetAccumulatorInitializedName>
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{
+      false};
+  std::atomic<HAL_SimDeviceHandle> simDevice;
+  SimDataValue<int32_t, HAL_MakeInt, GetAverageBitsName> averageBits{7};
+  SimDataValue<int32_t, HAL_MakeInt, GetOversampleBitsName> oversampleBits{0};
+  SimDataValue<double, HAL_MakeDouble, GetVoltageName> voltage{0.0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetAccumulatorInitializedName>
       accumulatorInitialized{false};
-  SimDataValue<int64_t, MakeLong, GetAccumulatorValueName> accumulatorValue{0};
-  SimDataValue<int64_t, MakeLong, GetAccumulatorCountName> accumulatorCount{0};
-  SimDataValue<int32_t, MakeInt, GetAccumulatorCenterName> accumulatorCenter{0};
-  SimDataValue<int32_t, MakeInt, GetAccumulatorDeadbandName>
+  SimDataValue<int64_t, HAL_MakeLong, GetAccumulatorValueName> accumulatorValue{
+      0};
+  SimDataValue<int64_t, HAL_MakeLong, GetAccumulatorCountName> accumulatorCount{
+      0};
+  SimDataValue<int32_t, HAL_MakeInt, GetAccumulatorCenterName>
+      accumulatorCenter{0};
+  SimDataValue<int32_t, HAL_MakeInt, GetAccumulatorDeadbandName>
       accumulatorDeadband{0};
 
   virtual void ResetData();
diff --git a/hal/src/main/native/sim/mockdata/AnalogOutDataInternal.h b/hal/src/main/native/sim/mockdata/AnalogOutDataInternal.h
index 84af837..da7d49f 100644
--- a/hal/src/main/native/sim/mockdata/AnalogOutDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/AnalogOutDataInternal.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.                                                               */
@@ -16,8 +16,8 @@
   HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
 
  public:
-  SimDataValue<double, MakeDouble, GetVoltageName> voltage{0.0};
-  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{0};
+  SimDataValue<double, HAL_MakeDouble, GetVoltageName> voltage{0.0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{0};
 
   virtual void ResetData();
 };
diff --git a/hal/src/main/native/sim/mockdata/AnalogTriggerDataInternal.h b/hal/src/main/native/sim/mockdata/AnalogTriggerDataInternal.h
index 131ba7a..61b3c19 100644
--- a/hal/src/main/native/sim/mockdata/AnalogTriggerDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/AnalogTriggerDataInternal.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.                                                               */
@@ -19,15 +19,15 @@
 
   static LLVM_ATTRIBUTE_ALWAYS_INLINE HAL_Value
   MakeTriggerModeValue(HALSIM_AnalogTriggerMode value) {
-    return MakeEnum(value);
+    return HAL_MakeEnum(value);
   }
 
  public:
-  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{0};
-  SimDataValue<double, MakeDouble, GetTriggerLowerBoundName> triggerLowerBound{
-      0};
-  SimDataValue<double, MakeDouble, GetTriggerUpperBoundName> triggerUpperBound{
-      0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{0};
+  SimDataValue<double, HAL_MakeDouble, GetTriggerLowerBoundName>
+      triggerLowerBound{0};
+  SimDataValue<double, HAL_MakeDouble, GetTriggerUpperBoundName>
+      triggerUpperBound{0};
   SimDataValue<HALSIM_AnalogTriggerMode, MakeTriggerModeValue,
                GetTriggerModeName>
       triggerMode{static_cast<HALSIM_AnalogTriggerMode>(0)};
diff --git a/hal/src/main/native/sim/mockdata/DIOData.cpp b/hal/src/main/native/sim/mockdata/DIOData.cpp
index ea66de3..a9c61fd 100644
--- a/hal/src/main/native/sim/mockdata/DIOData.cpp
+++ b/hal/src/main/native/sim/mockdata/DIOData.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.                                                               */
@@ -22,6 +22,7 @@
 DIOData* hal::SimDIOData;
 void DIOData::ResetData() {
   initialized.Reset(false);
+  simDevice = 0;
   value.Reset(true);
   pulseLength.Reset(0.0);
   isInput.Reset(true);
@@ -31,6 +32,10 @@
 extern "C" {
 void HALSIM_ResetDIOData(int32_t index) { SimDIOData[index].ResetData(); }
 
+HAL_SimDeviceHandle HALSIM_GetDIOSimDevice(int32_t index) {
+  return SimDIOData[index].simDevice;
+}
+
 #define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                          \
   HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, DIO##CAPINAME, SimDIOData, \
                                LOWERNAME)
diff --git a/hal/src/main/native/sim/mockdata/DIODataInternal.h b/hal/src/main/native/sim/mockdata/DIODataInternal.h
index 0b022f9..49e0f75 100644
--- a/hal/src/main/native/sim/mockdata/DIODataInternal.h
+++ b/hal/src/main/native/sim/mockdata/DIODataInternal.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.                                                               */
@@ -19,11 +19,13 @@
   HAL_SIMDATAVALUE_DEFINE_NAME(FilterIndex)
 
  public:
-  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
-  SimDataValue<HAL_Bool, MakeBoolean, GetValueName> value{true};
-  SimDataValue<double, MakeDouble, GetPulseLengthName> pulseLength{0.0};
-  SimDataValue<HAL_Bool, MakeBoolean, GetIsInputName> isInput{true};
-  SimDataValue<int32_t, MakeInt, GetFilterIndexName> filterIndex{-1};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{
+      false};
+  std::atomic<HAL_SimDeviceHandle> simDevice;
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetValueName> value{true};
+  SimDataValue<double, HAL_MakeDouble, GetPulseLengthName> pulseLength{0.0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetIsInputName> isInput{true};
+  SimDataValue<int32_t, HAL_MakeInt, GetFilterIndexName> filterIndex{-1};
 
   virtual void ResetData();
 };
diff --git a/hal/src/main/native/sim/mockdata/DigitalPWMDataInternal.h b/hal/src/main/native/sim/mockdata/DigitalPWMDataInternal.h
index 00d8b4a..09d5903 100644
--- a/hal/src/main/native/sim/mockdata/DigitalPWMDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/DigitalPWMDataInternal.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.                                                               */
@@ -17,9 +17,10 @@
   HAL_SIMDATAVALUE_DEFINE_NAME(Pin)
 
  public:
-  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
-  SimDataValue<double, MakeDouble, GetDutyCycleName> dutyCycle{0.0};
-  SimDataValue<int32_t, MakeInt, GetPinName> pin{0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{
+      false};
+  SimDataValue<double, HAL_MakeDouble, GetDutyCycleName> dutyCycle{0.0};
+  SimDataValue<int32_t, HAL_MakeInt, GetPinName> pin{0};
 
   virtual void ResetData();
 };
diff --git a/hal/src/main/native/sim/mockdata/DriverStationData.cpp b/hal/src/main/native/sim/mockdata/DriverStationData.cpp
index d72d6b3..ece98c8 100644
--- a/hal/src/main/native/sim/mockdata/DriverStationData.cpp
+++ b/hal/src/main/native/sim/mockdata/DriverStationData.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.                                                               */
@@ -46,7 +46,7 @@
   matchTime.Reset(0.0);
 
   {
-    std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+    std::scoped_lock lock(m_joystickDataMutex);
     m_joystickAxes = std::make_unique<HAL_JoystickAxes[]>(6);
     m_joystickPOVs = std::make_unique<HAL_JoystickPOVs[]>(6);
     m_joystickButtons = std::make_unique<HAL_JoystickButtons[]>(6);
@@ -63,7 +63,7 @@
     }
   }
   {
-    std::lock_guard<wpi::spinlock> lock(m_matchInfoMutex);
+    std::scoped_lock lock(m_matchInfoMutex);
 
     m_matchInfo = std::make_unique<HAL_MatchInfo>();
   }
@@ -71,22 +71,22 @@
 
 void DriverStationData::GetJoystickAxes(int32_t joystickNum,
                                         HAL_JoystickAxes* axes) {
-  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  std::scoped_lock lock(m_joystickDataMutex);
   *axes = m_joystickAxes[joystickNum];
 }
 void DriverStationData::GetJoystickPOVs(int32_t joystickNum,
                                         HAL_JoystickPOVs* povs) {
-  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  std::scoped_lock lock(m_joystickDataMutex);
   *povs = m_joystickPOVs[joystickNum];
 }
 void DriverStationData::GetJoystickButtons(int32_t joystickNum,
                                            HAL_JoystickButtons* buttons) {
-  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  std::scoped_lock lock(m_joystickDataMutex);
   *buttons = m_joystickButtons[joystickNum];
 }
 void DriverStationData::GetJoystickDescriptor(
     int32_t joystickNum, HAL_JoystickDescriptor* descriptor) {
-  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  std::scoped_lock lock(m_joystickDataMutex);
   *descriptor = m_joystickDescriptor[joystickNum];
   // Always ensure name is null terminated
   descriptor->name[255] = '\0';
@@ -95,49 +95,49 @@
                                            int64_t* outputs,
                                            int32_t* leftRumble,
                                            int32_t* rightRumble) {
-  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  std::scoped_lock lock(m_joystickDataMutex);
   *leftRumble = m_joystickOutputs[joystickNum].leftRumble;
   *outputs = m_joystickOutputs[joystickNum].outputs;
   *rightRumble = m_joystickOutputs[joystickNum].rightRumble;
 }
 void DriverStationData::GetMatchInfo(HAL_MatchInfo* info) {
-  std::lock_guard<wpi::spinlock> lock(m_matchInfoMutex);
+  std::scoped_lock lock(m_matchInfoMutex);
   *info = *m_matchInfo;
 }
 
 void DriverStationData::SetJoystickAxes(int32_t joystickNum,
                                         const HAL_JoystickAxes* axes) {
-  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  std::scoped_lock lock(m_joystickDataMutex);
   m_joystickAxes[joystickNum] = *axes;
 }
 void DriverStationData::SetJoystickPOVs(int32_t joystickNum,
                                         const HAL_JoystickPOVs* povs) {
-  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  std::scoped_lock lock(m_joystickDataMutex);
   m_joystickPOVs[joystickNum] = *povs;
 }
 void DriverStationData::SetJoystickButtons(int32_t joystickNum,
                                            const HAL_JoystickButtons* buttons) {
-  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  std::scoped_lock lock(m_joystickDataMutex);
   m_joystickButtons[joystickNum] = *buttons;
 }
 
 void DriverStationData::SetJoystickDescriptor(
     int32_t joystickNum, const HAL_JoystickDescriptor* descriptor) {
-  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  std::scoped_lock lock(m_joystickDataMutex);
   m_joystickDescriptor[joystickNum] = *descriptor;
 }
 
 void DriverStationData::SetJoystickOutputs(int32_t joystickNum, int64_t outputs,
                                            int32_t leftRumble,
                                            int32_t rightRumble) {
-  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  std::scoped_lock lock(m_joystickDataMutex);
   m_joystickOutputs[joystickNum].leftRumble = leftRumble;
   m_joystickOutputs[joystickNum].outputs = outputs;
   m_joystickOutputs[joystickNum].rightRumble = rightRumble;
 }
 
 void DriverStationData::SetMatchInfo(const HAL_MatchInfo* info) {
-  std::lock_guard<wpi::spinlock> lock(m_matchInfoMutex);
+  std::scoped_lock lock(m_matchInfoMutex);
   *m_matchInfo = *info;
   *(std::end(m_matchInfo->eventName) - 1) = '\0';
 }
diff --git a/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h b/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h
index f7eb132..fdeb3c6 100644
--- a/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/DriverStationDataInternal.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.                                                               */
@@ -29,7 +29,7 @@
 
   static LLVM_ATTRIBUTE_ALWAYS_INLINE HAL_Value
   MakeAllianceStationIdValue(HAL_AllianceStationID value) {
-    return MakeEnum(value);
+    return HAL_MakeEnum(value);
   }
 
  public:
@@ -58,16 +58,17 @@
 
   void NotifyNewData();
 
-  SimDataValue<HAL_Bool, MakeBoolean, GetEnabledName> enabled{false};
-  SimDataValue<HAL_Bool, MakeBoolean, GetAutonomousName> autonomous{false};
-  SimDataValue<HAL_Bool, MakeBoolean, GetTestName> test{false};
-  SimDataValue<HAL_Bool, MakeBoolean, GetEStopName> eStop{false};
-  SimDataValue<HAL_Bool, MakeBoolean, GetFmsAttachedName> fmsAttached{false};
-  SimDataValue<HAL_Bool, MakeBoolean, GetDsAttachedName> dsAttached{true};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetEnabledName> enabled{false};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetAutonomousName> autonomous{false};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetTestName> test{false};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetEStopName> eStop{false};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetFmsAttachedName> fmsAttached{
+      false};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetDsAttachedName> dsAttached{true};
   SimDataValue<HAL_AllianceStationID, MakeAllianceStationIdValue,
                GetAllianceStationIdName>
       allianceStationId{static_cast<HAL_AllianceStationID>(0)};
-  SimDataValue<double, MakeDouble, GetMatchTimeName> matchTime{0.0};
+  SimDataValue<double, HAL_MakeDouble, GetMatchTimeName> matchTime{0.0};
 
  private:
   wpi::spinlock m_joystickDataMutex;
diff --git a/hal/src/main/native/sim/mockdata/EncoderData.cpp b/hal/src/main/native/sim/mockdata/EncoderData.cpp
index 59ba48f..33bd073 100644
--- a/hal/src/main/native/sim/mockdata/EncoderData.cpp
+++ b/hal/src/main/native/sim/mockdata/EncoderData.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.                                                               */
@@ -22,7 +22,9 @@
 EncoderData* hal::SimEncoderData;
 void EncoderData::ResetData() {
   digitalChannelA = 0;
+  digitalChannelB = 0;
   initialized.Reset(false);
+  simDevice = 0;
   count.Reset(0);
   period.Reset(std::numeric_limits<double>::max());
   reset.Reset(false);
@@ -38,10 +40,18 @@
   SimEncoderData[index].ResetData();
 }
 
-int16_t HALSIM_GetDigitalChannelA(int32_t index) {
+int32_t HALSIM_GetEncoderDigitalChannelA(int32_t index) {
   return SimEncoderData[index].digitalChannelA;
 }
 
+int32_t HALSIM_GetEncoderDigitalChannelB(int32_t index) {
+  return SimEncoderData[index].digitalChannelB;
+}
+
+HAL_SimDeviceHandle HALSIM_GetEncoderSimDevice(int32_t index) {
+  return SimEncoderData[index].simDevice;
+}
+
 #define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                  \
   HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, Encoder##CAPINAME, \
                                SimEncoderData, LOWERNAME)
diff --git a/hal/src/main/native/sim/mockdata/EncoderDataInternal.h b/hal/src/main/native/sim/mockdata/EncoderDataInternal.h
index 657d977..389289c 100644
--- a/hal/src/main/native/sim/mockdata/EncoderDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/EncoderDataInternal.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.                                                               */
@@ -26,18 +26,23 @@
   HAL_SIMDATAVALUE_DEFINE_NAME(DistancePerPulse)
 
  public:
-  std::atomic<int16_t> digitalChannelA{0};
-  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
-  SimDataValue<int32_t, MakeInt, GetCountName> count{0};
-  SimDataValue<double, MakeDouble, GetPeriodName> period{
-      std::numeric_limits<double>::max()};
-  SimDataValue<HAL_Bool, MakeBoolean, GetResetName> reset{false};
-  SimDataValue<double, MakeDouble, GetMaxPeriodName> maxPeriod{0};
-  SimDataValue<HAL_Bool, MakeBoolean, GetDirectionName> direction{false};
-  SimDataValue<HAL_Bool, MakeBoolean, GetReverseDirectionName> reverseDirection{
+  std::atomic<int32_t> digitalChannelA{0};
+  std::atomic<int32_t> digitalChannelB{0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{
       false};
-  SimDataValue<int32_t, MakeInt, GetSamplesToAverageName> samplesToAverage{0};
-  SimDataValue<double, MakeDouble, GetDistancePerPulseName> distancePerPulse{1};
+  std::atomic<HAL_SimDeviceHandle> simDevice;
+  SimDataValue<int32_t, HAL_MakeInt, GetCountName> count{0};
+  SimDataValue<double, HAL_MakeDouble, GetPeriodName> period{
+      (std::numeric_limits<double>::max)()};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetResetName> reset{false};
+  SimDataValue<double, HAL_MakeDouble, GetMaxPeriodName> maxPeriod{0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetDirectionName> direction{false};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetReverseDirectionName>
+      reverseDirection{false};
+  SimDataValue<int32_t, HAL_MakeInt, GetSamplesToAverageName> samplesToAverage{
+      0};
+  SimDataValue<double, HAL_MakeDouble, GetDistancePerPulseName>
+      distancePerPulse{1};
 
   virtual void ResetData();
 };
diff --git a/hal/src/main/native/sim/mockdata/HALValueInternal.h b/hal/src/main/native/sim/mockdata/HALValueInternal.h
deleted file mode 100644
index f659403..0000000
--- a/hal/src/main/native/sim/mockdata/HALValueInternal.h
+++ /dev/null
@@ -1,27 +0,0 @@
-/*----------------------------------------------------------------------------*/
-/* Copyright (c) 2017-2018 FIRST. All Rights Reserved.                        */
-/* Open Source Software - may be modified and shared by FRC teams. The code   */
-/* must be accompanied by the FIRST BSD license file in the root directory of */
-/* the project.                                                               */
-/*----------------------------------------------------------------------------*/
-
-#pragma once
-
-#include <memory>
-#include <string>
-
-#include "mockdata/HALValue.h"
-#include "mockdata/wpi/StringRef.h"
-
-namespace hal {
-
-class Value;
-
-void ConvertToC(const Value& in, HAL_Value* out);
-std::shared_ptr<Value> ConvertFromC(const HAL_Value& value);
-void ConvertToC(wpi::StringRef in, HALString* out);
-inline wpi::StringRef ConvertFromC(const HALString& str) {
-  return wpi::StringRef(str.str, str.len);
-}
-
-}  // namespace hal
diff --git a/hal/src/main/native/sim/mockdata/I2CDataInternal.h b/hal/src/main/native/sim/mockdata/I2CDataInternal.h
index 1c2df0e..c799bb7 100644
--- a/hal/src/main/native/sim/mockdata/I2CDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/I2CDataInternal.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.                                                               */
@@ -22,7 +22,8 @@
              int32_t sendSize);
   void Read(int32_t deviceAddress, uint8_t* buffer, int32_t count);
 
-  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{
+      false};
   SimCallbackRegistry<HAL_BufferCallback, GetReadName> read;
   SimCallbackRegistry<HAL_ConstBufferCallback, GetWriteName> write;
 
diff --git a/hal/src/main/native/sim/mockdata/PCMDataInternal.h b/hal/src/main/native/sim/mockdata/PCMDataInternal.h
index 4144987..0c7b99b 100644
--- a/hal/src/main/native/sim/mockdata/PCMDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/PCMDataInternal.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.                                                               */
@@ -31,21 +31,22 @@
   }
 
  public:
-  SimDataValue<HAL_Bool, MakeBoolean, GetSolenoidInitializedName,
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetSolenoidInitializedName,
                GetSolenoidInitializedDefault>
       solenoidInitialized[kNumSolenoidChannels];
-  SimDataValue<HAL_Bool, MakeBoolean, GetSolenoidOutputName,
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetSolenoidOutputName,
                GetSolenoidOutputDefault>
       solenoidOutput[kNumSolenoidChannels];
-  SimDataValue<HAL_Bool, MakeBoolean, GetCompressorInitializedName>
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetCompressorInitializedName>
       compressorInitialized{false};
-  SimDataValue<HAL_Bool, MakeBoolean, GetCompressorOnName> compressorOn{false};
-  SimDataValue<HAL_Bool, MakeBoolean, GetClosedLoopEnabledName>
-      closedLoopEnabled{true};
-  SimDataValue<HAL_Bool, MakeBoolean, GetPressureSwitchName> pressureSwitch{
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetCompressorOnName> compressorOn{
       false};
-  SimDataValue<double, MakeDouble, GetCompressorCurrentName> compressorCurrent{
-      0.0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetClosedLoopEnabledName>
+      closedLoopEnabled{true};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetPressureSwitchName> pressureSwitch{
+      false};
+  SimDataValue<double, HAL_MakeDouble, GetCompressorCurrentName>
+      compressorCurrent{0.0};
 
   virtual void ResetData();
 };
diff --git a/hal/src/main/native/sim/mockdata/PDPDataInternal.h b/hal/src/main/native/sim/mockdata/PDPDataInternal.h
index a7170c7..8d45416 100644
--- a/hal/src/main/native/sim/mockdata/PDPDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/PDPDataInternal.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.                                                               */
@@ -23,10 +23,11 @@
   }
 
  public:
-  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
-  SimDataValue<double, MakeDouble, GetTemperatureName> temperature{0.0};
-  SimDataValue<double, MakeDouble, GetVoltageName> voltage{12.0};
-  SimDataValue<double, MakeDouble, GetCurrentName, GetCurrentDefault>
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{
+      false};
+  SimDataValue<double, HAL_MakeDouble, GetTemperatureName> temperature{0.0};
+  SimDataValue<double, HAL_MakeDouble, GetVoltageName> voltage{12.0};
+  SimDataValue<double, HAL_MakeDouble, GetCurrentName, GetCurrentDefault>
       current[kNumPDPChannels];
 
   virtual void ResetData();
diff --git a/hal/src/main/native/sim/mockdata/PWMDataInternal.h b/hal/src/main/native/sim/mockdata/PWMDataInternal.h
index 85eae44..248b7b3 100644
--- a/hal/src/main/native/sim/mockdata/PWMDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/PWMDataInternal.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.                                                               */
@@ -20,12 +20,13 @@
   HAL_SIMDATAVALUE_DEFINE_NAME(ZeroLatch)
 
  public:
-  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
-  SimDataValue<int32_t, MakeInt, GetRawValueName> rawValue{0};
-  SimDataValue<double, MakeDouble, GetSpeedName> speed{0};
-  SimDataValue<double, MakeDouble, GetPositionName> position{0};
-  SimDataValue<int32_t, MakeInt, GetPeriodScaleName> periodScale{0};
-  SimDataValue<HAL_Bool, MakeBoolean, GetZeroLatchName> zeroLatch{false};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{
+      false};
+  SimDataValue<int32_t, HAL_MakeInt, GetRawValueName> rawValue{0};
+  SimDataValue<double, HAL_MakeDouble, GetSpeedName> speed{0};
+  SimDataValue<double, HAL_MakeDouble, GetPositionName> position{0};
+  SimDataValue<int32_t, HAL_MakeInt, GetPeriodScaleName> periodScale{0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetZeroLatchName> zeroLatch{false};
 
   virtual void ResetData();
 };
diff --git a/hal/src/main/native/sim/mockdata/RelayDataInternal.h b/hal/src/main/native/sim/mockdata/RelayDataInternal.h
index 88e79ff..cb38388 100644
--- a/hal/src/main/native/sim/mockdata/RelayDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/RelayDataInternal.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.                                                               */
@@ -18,12 +18,12 @@
   HAL_SIMDATAVALUE_DEFINE_NAME(Reverse)
 
  public:
-  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedForwardName>
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedForwardName>
       initializedForward{false};
-  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedReverseName>
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedReverseName>
       initializedReverse{false};
-  SimDataValue<HAL_Bool, MakeBoolean, GetForwardName> forward{false};
-  SimDataValue<HAL_Bool, MakeBoolean, GetReverseName> reverse{false};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetForwardName> forward{false};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetReverseName> reverse{false};
 
   virtual void ResetData();
 };
diff --git a/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h b/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h
index 92aa0c8..cc74fa2 100644
--- a/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/RoboRioDataInternal.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.                                                               */
@@ -29,22 +29,26 @@
   HAL_SIMDATAVALUE_DEFINE_NAME(UserFaults3V3)
 
  public:
-  SimDataValue<HAL_Bool, MakeBoolean, GetFPGAButtonName> fpgaButton{false};
-  SimDataValue<double, MakeDouble, GetVInVoltageName> vInVoltage{0.0};
-  SimDataValue<double, MakeDouble, GetVInCurrentName> vInCurrent{0.0};
-  SimDataValue<double, MakeDouble, GetUserVoltage6VName> userVoltage6V{6.0};
-  SimDataValue<double, MakeDouble, GetUserCurrent6VName> userCurrent6V{0.0};
-  SimDataValue<HAL_Bool, MakeBoolean, GetUserActive6VName> userActive6V{false};
-  SimDataValue<double, MakeDouble, GetUserVoltage5VName> userVoltage5V{5.0};
-  SimDataValue<double, MakeDouble, GetUserCurrent5VName> userCurrent5V{0.0};
-  SimDataValue<HAL_Bool, MakeBoolean, GetUserActive5VName> userActive5V{false};
-  SimDataValue<double, MakeDouble, GetUserVoltage3V3Name> userVoltage3V3{3.3};
-  SimDataValue<double, MakeDouble, GetUserCurrent3V3Name> userCurrent3V3{0.0};
-  SimDataValue<HAL_Bool, MakeBoolean, GetUserActive3V3Name> userActive3V3{
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetFPGAButtonName> fpgaButton{false};
+  SimDataValue<double, HAL_MakeDouble, GetVInVoltageName> vInVoltage{0.0};
+  SimDataValue<double, HAL_MakeDouble, GetVInCurrentName> vInCurrent{0.0};
+  SimDataValue<double, HAL_MakeDouble, GetUserVoltage6VName> userVoltage6V{6.0};
+  SimDataValue<double, HAL_MakeDouble, GetUserCurrent6VName> userCurrent6V{0.0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetUserActive6VName> userActive6V{
       false};
-  SimDataValue<int32_t, MakeInt, GetUserFaults6VName> userFaults6V{0};
-  SimDataValue<int32_t, MakeInt, GetUserFaults5VName> userFaults5V{0};
-  SimDataValue<int32_t, MakeInt, GetUserFaults3V3Name> userFaults3V3{0};
+  SimDataValue<double, HAL_MakeDouble, GetUserVoltage5VName> userVoltage5V{5.0};
+  SimDataValue<double, HAL_MakeDouble, GetUserCurrent5VName> userCurrent5V{0.0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetUserActive5VName> userActive5V{
+      false};
+  SimDataValue<double, HAL_MakeDouble, GetUserVoltage3V3Name> userVoltage3V3{
+      3.3};
+  SimDataValue<double, HAL_MakeDouble, GetUserCurrent3V3Name> userCurrent3V3{
+      0.0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetUserActive3V3Name> userActive3V3{
+      false};
+  SimDataValue<int32_t, HAL_MakeInt, GetUserFaults6VName> userFaults6V{0};
+  SimDataValue<int32_t, HAL_MakeInt, GetUserFaults5VName> userFaults5V{0};
+  SimDataValue<int32_t, HAL_MakeInt, GetUserFaults3V3Name> userFaults3V3{0};
 
   virtual void ResetData();
 };
diff --git a/hal/src/main/native/sim/mockdata/SPIAccelerometerDataInternal.h b/hal/src/main/native/sim/mockdata/SPIAccelerometerDataInternal.h
index ee9f79d..661e01b 100644
--- a/hal/src/main/native/sim/mockdata/SPIAccelerometerDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/SPIAccelerometerDataInternal.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.                                                               */
@@ -19,11 +19,11 @@
   HAL_SIMDATAVALUE_DEFINE_NAME(Z)
 
  public:
-  SimDataValue<HAL_Bool, MakeBoolean, GetActiveName> active{false};
-  SimDataValue<int32_t, MakeInt, GetRangeName> range{0};
-  SimDataValue<double, MakeDouble, GetXName> x{0.0};
-  SimDataValue<double, MakeDouble, GetYName> y{0.0};
-  SimDataValue<double, MakeDouble, GetZName> z{0.0};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetActiveName> active{false};
+  SimDataValue<int32_t, HAL_MakeInt, GetRangeName> range{0};
+  SimDataValue<double, HAL_MakeDouble, GetXName> x{0.0};
+  SimDataValue<double, HAL_MakeDouble, GetYName> y{0.0};
+  SimDataValue<double, HAL_MakeDouble, GetZName> z{0.0};
 
   virtual void ResetData();
 };
diff --git a/hal/src/main/native/sim/mockdata/SPIDataInternal.h b/hal/src/main/native/sim/mockdata/SPIDataInternal.h
index b10e741..44868d2 100644
--- a/hal/src/main/native/sim/mockdata/SPIDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/SPIDataInternal.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.                                                               */
@@ -27,7 +27,8 @@
   int32_t ReadAutoReceivedData(uint32_t* buffer, int32_t numToRead,
                                double timeout, int32_t* status);
 
-  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
+  SimDataValue<HAL_Bool, HAL_MakeBoolean, GetInitializedName> initialized{
+      false};
   SimCallbackRegistry<HAL_BufferCallback, GetReadName> read;
   SimCallbackRegistry<HAL_ConstBufferCallback, GetWriteName> write;
   SimCallbackRegistry<HAL_SpiReadAutoReceiveBufferCallback, GetAutoReceiveName>
diff --git a/hal/src/main/native/sim/mockdata/SimDeviceData.cpp b/hal/src/main/native/sim/mockdata/SimDeviceData.cpp
new file mode 100644
index 0000000..a703257
--- /dev/null
+++ b/hal/src/main/native/sim/mockdata/SimDeviceData.cpp
@@ -0,0 +1,414 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "mockdata/SimDeviceData.h"  // NOLINT(build/include_order)
+
+#include <algorithm>
+
+#include "SimDeviceDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeSimDeviceData() {
+  static SimDeviceData sdd;
+  ::hal::SimSimDeviceData = &sdd;
+}
+}  // namespace init
+}  // namespace hal
+
+SimDeviceData* hal::SimSimDeviceData;
+
+SimDeviceData::Device* SimDeviceData::LookupDevice(HAL_SimDeviceHandle handle) {
+  if (handle <= 0) return nullptr;
+  --handle;
+  if (static_cast<uint32_t>(handle) >= m_devices.size() || !m_devices[handle])
+    return nullptr;
+  return m_devices[handle].get();
+}
+
+SimDeviceData::Value* SimDeviceData::LookupValue(HAL_SimValueHandle handle) {
+  if (handle <= 0) return nullptr;
+
+  // look up device
+  Device* deviceImpl = LookupDevice(handle >> 16);
+  if (!deviceImpl) return nullptr;
+
+  // look up value
+  handle &= 0xffff;
+  --handle;
+  if (static_cast<uint32_t>(handle) >= deviceImpl->values.size() ||
+      !deviceImpl->values[handle])
+    return nullptr;
+
+  return deviceImpl->values[handle].get();
+}
+
+HAL_SimDeviceHandle SimDeviceData::CreateDevice(const char* name) {
+  std::scoped_lock lock(m_mutex);
+
+  // check for duplicates and don't overwrite them
+  auto it = m_deviceMap.find(name);
+  if (it != m_deviceMap.end()) return 0;
+
+  // don't allow more than 4096 devices (limit driven by 12-bit allocation in
+  // value changed callback uid)
+  if (m_devices.size() >= 4095) return 0;
+
+  // create and save
+  auto deviceImpl = std::make_shared<Device>(name);
+  HAL_SimDeviceHandle deviceHandle = m_devices.emplace_back(deviceImpl) + 1;
+  deviceImpl->handle = deviceHandle;
+  m_deviceMap[name] = deviceImpl;
+
+  // notify callbacks
+  m_deviceCreated(name, deviceHandle);
+
+  return deviceHandle;
+}
+
+void SimDeviceData::FreeDevice(HAL_SimDeviceHandle handle) {
+  std::scoped_lock lock(m_mutex);
+  --handle;
+
+  // see if it exists
+  if (handle < 0 || static_cast<uint32_t>(handle) >= m_devices.size()) return;
+  auto deviceImpl = std::move(m_devices[handle]);
+  if (!deviceImpl) return;
+
+  // remove from map
+  m_deviceMap.erase(deviceImpl->name);
+
+  // remove from vector
+  m_devices.erase(handle);
+
+  // notify callbacks
+  m_deviceFreed(deviceImpl->name.c_str(), handle + 1);
+}
+
+HAL_SimValueHandle SimDeviceData::CreateValue(HAL_SimDeviceHandle device,
+                                              const char* name, bool readonly,
+                                              int32_t numOptions,
+                                              const char** options,
+                                              const HAL_Value& initialValue) {
+  std::scoped_lock lock(m_mutex);
+
+  // look up device
+  Device* deviceImpl = LookupDevice(device);
+  if (!deviceImpl) return 0;
+
+  // check for duplicates and don't overwrite them
+  auto it = deviceImpl->valueMap.find(name);
+  if (it != deviceImpl->valueMap.end()) return 0;
+
+  // don't allow more than 4096 values per device (limit driven by 12-bit
+  // allocation in value changed callback uid)
+  if (deviceImpl->values.size() >= 4095) return 0;
+
+  // create and save; encode device into handle
+  auto valueImplPtr = std::make_unique<Value>(name, readonly, initialValue);
+  Value* valueImpl = valueImplPtr.get();
+  HAL_SimValueHandle valueHandle =
+      (device << 16) |
+      (deviceImpl->values.emplace_back(std::move(valueImplPtr)) + 1);
+  valueImpl->handle = valueHandle;
+  // copy options (if any provided)
+  if (numOptions > 0 && options) {
+    valueImpl->enumOptions.reserve(numOptions);
+    valueImpl->cstrEnumOptions.reserve(numOptions);
+    for (int32_t i = 0; i < numOptions; ++i) {
+      valueImpl->enumOptions.emplace_back(options[i]);
+      // point to our copy of the string, not the passed-in one
+      valueImpl->cstrEnumOptions.emplace_back(
+          valueImpl->enumOptions.back().c_str());
+    }
+  }
+  deviceImpl->valueMap[name] = valueImpl;
+
+  // notify callbacks
+  deviceImpl->valueCreated(name, valueHandle, readonly, &initialValue);
+
+  return valueHandle;
+}
+
+HAL_Value SimDeviceData::GetValue(HAL_SimValueHandle handle) {
+  std::scoped_lock lock(m_mutex);
+  Value* valueImpl = LookupValue(handle);
+
+  if (!valueImpl) {
+    HAL_Value value;
+    value.data.v_int = 0;
+    value.type = HAL_UNASSIGNED;
+    return value;
+  }
+
+  return valueImpl->value;
+}
+
+void SimDeviceData::SetValue(HAL_SimValueHandle handle,
+                             const HAL_Value& value) {
+  std::scoped_lock lock(m_mutex);
+  Value* valueImpl = LookupValue(handle);
+  if (!valueImpl) return;
+
+  valueImpl->value = value;
+
+  // notify callbacks
+  valueImpl->changed(valueImpl->name.c_str(), valueImpl->handle,
+                     valueImpl->readonly, &value);
+}
+
+int32_t SimDeviceData::RegisterDeviceCreatedCallback(
+    const char* prefix, void* param, HALSIM_SimDeviceCallback callback,
+    bool initialNotify) {
+  std::scoped_lock lock(m_mutex);
+
+  // register callback
+  int32_t index = m_deviceCreated.Register(prefix, param, callback);
+
+  // initial notifications
+  if (initialNotify) {
+    for (auto&& device : m_devices)
+      callback(device->name.c_str(), param, device->handle);
+  }
+
+  return index;
+}
+
+void SimDeviceData::CancelDeviceCreatedCallback(int32_t uid) {
+  if (uid <= 0) return;
+  std::scoped_lock lock(m_mutex);
+  m_deviceCreated.Cancel(uid);
+}
+
+int32_t SimDeviceData::RegisterDeviceFreedCallback(
+    const char* prefix, void* param, HALSIM_SimDeviceCallback callback) {
+  std::scoped_lock lock(m_mutex);
+  return m_deviceFreed.Register(prefix, param, callback);
+}
+
+void SimDeviceData::CancelDeviceFreedCallback(int32_t uid) {
+  if (uid <= 0) return;
+  std::scoped_lock lock(m_mutex);
+  m_deviceFreed.Cancel(uid);
+}
+
+HAL_SimDeviceHandle SimDeviceData::GetDeviceHandle(const char* name) {
+  std::scoped_lock lock(m_mutex);
+  auto it = m_deviceMap.find(name);
+  if (it == m_deviceMap.end()) return 0;
+  if (auto deviceImpl = it->getValue().lock())
+    return deviceImpl->handle;
+  else
+    return 0;
+}
+
+const char* SimDeviceData::GetDeviceName(HAL_SimDeviceHandle handle) {
+  std::scoped_lock lock(m_mutex);
+
+  // look up device
+  Device* deviceImpl = LookupDevice(handle);
+  if (!deviceImpl) return nullptr;
+
+  return deviceImpl->name.c_str();
+}
+
+void SimDeviceData::EnumerateDevices(const char* prefix, void* param,
+                                     HALSIM_SimDeviceCallback callback) {
+  std::scoped_lock lock(m_mutex);
+  for (auto&& device : m_devices) {
+    if (wpi::StringRef{device->name}.startswith(prefix))
+      callback(device->name.c_str(), param, device->handle);
+  }
+}
+
+int32_t SimDeviceData::RegisterValueCreatedCallback(
+    HAL_SimDeviceHandle device, void* param, HALSIM_SimValueCallback callback,
+    bool initialNotify) {
+  std::scoped_lock lock(m_mutex);
+  Device* deviceImpl = LookupDevice(device);
+  if (!deviceImpl) return -1;
+
+  // register callback
+  int32_t index = deviceImpl->valueCreated.Register(callback, param);
+
+  // initial notifications
+  if (initialNotify) {
+    for (auto&& value : deviceImpl->values)
+      callback(value->name.c_str(), param, value->handle, value->readonly,
+               &value->value);
+  }
+
+  // encode device into uid
+  return (device << 16) | (index & 0xffff);
+}
+
+void SimDeviceData::CancelValueCreatedCallback(int32_t uid) {
+  if (uid <= 0) return;
+  std::scoped_lock lock(m_mutex);
+  Device* deviceImpl = LookupDevice(uid >> 16);
+  if (!deviceImpl) return;
+  deviceImpl->valueCreated.Cancel(uid & 0xffff);
+}
+
+int32_t SimDeviceData::RegisterValueChangedCallback(
+    HAL_SimValueHandle handle, void* param, HALSIM_SimValueCallback callback,
+    bool initialNotify) {
+  std::scoped_lock lock(m_mutex);
+  Value* valueImpl = LookupValue(handle);
+  if (!valueImpl) return -1;
+
+  // register callback
+  int32_t index = valueImpl->changed.Register(callback, param);
+
+  // initial notification
+  if (initialNotify)
+    callback(valueImpl->name.c_str(), param, valueImpl->handle,
+             valueImpl->readonly, &valueImpl->value);
+
+  // encode device and value into uid
+  return (((handle >> 16) & 0xfff) << 19) | ((handle & 0xfff) << 7) |
+         (index & 0x7f);
+}
+
+void SimDeviceData::CancelValueChangedCallback(int32_t uid) {
+  if (uid <= 0) return;
+  std::scoped_lock lock(m_mutex);
+  Value* valueImpl = LookupValue(((uid >> 19) << 16) | ((uid >> 7) & 0xfff));
+  if (!valueImpl) return;
+  valueImpl->changed.Cancel(uid & 0x7f);
+}
+
+HAL_SimValueHandle SimDeviceData::GetValueHandle(HAL_SimDeviceHandle device,
+                                                 const char* name) {
+  std::scoped_lock lock(m_mutex);
+  Device* deviceImpl = LookupDevice(device);
+  if (!deviceImpl) return 0;
+
+  // lookup value
+  auto it = deviceImpl->valueMap.find(name);
+  if (it == deviceImpl->valueMap.end()) return 0;
+  if (!it->getValue()) return 0;
+  return it->getValue()->handle;
+}
+
+void SimDeviceData::EnumerateValues(HAL_SimDeviceHandle device, void* param,
+                                    HALSIM_SimValueCallback callback) {
+  std::scoped_lock lock(m_mutex);
+  Device* deviceImpl = LookupDevice(device);
+  if (!deviceImpl) return;
+
+  for (auto&& value : deviceImpl->values)
+    callback(value->name.c_str(), param, value->handle, value->readonly,
+             &value->value);
+}
+
+const char** SimDeviceData::GetValueEnumOptions(HAL_SimValueHandle handle,
+                                                int32_t* numOptions) {
+  *numOptions = 0;
+
+  std::scoped_lock lock(m_mutex);
+  Value* valueImpl = LookupValue(handle);
+  if (!valueImpl) return nullptr;
+
+  // get list of options (safe to return as they never change)
+  auto& options = valueImpl->cstrEnumOptions;
+  *numOptions = options.size();
+  return options.data();
+}
+
+void SimDeviceData::ResetData() {
+  std::scoped_lock lock(m_mutex);
+  m_devices.clear();
+  m_deviceMap.clear();
+  m_deviceCreated.Reset();
+  m_deviceFreed.Reset();
+}
+
+extern "C" {
+
+int32_t HALSIM_RegisterSimDeviceCreatedCallback(
+    const char* prefix, void* param, HALSIM_SimDeviceCallback callback,
+    HAL_Bool initialNotify) {
+  return SimSimDeviceData->RegisterDeviceCreatedCallback(
+      prefix, param, callback, initialNotify);
+}
+
+void HALSIM_CancelSimDeviceCreatedCallback(int32_t uid) {
+  SimSimDeviceData->CancelDeviceCreatedCallback(uid);
+}
+
+int32_t HALSIM_RegisterSimDeviceFreedCallback(
+    const char* prefix, void* param, HALSIM_SimDeviceCallback callback) {
+  return SimSimDeviceData->RegisterDeviceFreedCallback(prefix, param, callback);
+}
+
+void HALSIM_CancelSimDeviceFreedCallback(int32_t uid) {
+  SimSimDeviceData->CancelDeviceFreedCallback(uid);
+}
+
+HAL_SimDeviceHandle HALSIM_GetSimDeviceHandle(const char* name) {
+  return SimSimDeviceData->GetDeviceHandle(name);
+}
+
+const char* HALSIM_GetSimDeviceName(HAL_SimDeviceHandle handle) {
+  return SimSimDeviceData->GetDeviceName(handle);
+}
+
+HAL_SimDeviceHandle HALSIM_GetSimValueDeviceHandle(HAL_SimValueHandle handle) {
+  if (handle <= 0) return 0;
+  return handle >> 16;
+}
+
+void HALSIM_EnumerateSimDevices(const char* prefix, void* param,
+                                HALSIM_SimDeviceCallback callback) {
+  SimSimDeviceData->EnumerateDevices(prefix, param, callback);
+}
+
+int32_t HALSIM_RegisterSimValueCreatedCallback(HAL_SimDeviceHandle device,
+                                               void* param,
+                                               HALSIM_SimValueCallback callback,
+                                               HAL_Bool initialNotify) {
+  return SimSimDeviceData->RegisterValueCreatedCallback(device, param, callback,
+                                                        initialNotify);
+}
+
+void HALSIM_CancelSimValueCreatedCallback(int32_t uid) {
+  SimSimDeviceData->CancelValueCreatedCallback(uid);
+}
+
+int32_t HALSIM_RegisterSimValueChangedCallback(HAL_SimValueHandle handle,
+                                               void* param,
+                                               HALSIM_SimValueCallback callback,
+                                               HAL_Bool initialNotify) {
+  return SimSimDeviceData->RegisterValueChangedCallback(handle, param, callback,
+                                                        initialNotify);
+}
+
+void HALSIM_CancelSimValueChangedCallback(int32_t uid) {
+  SimSimDeviceData->CancelValueChangedCallback(uid);
+}
+
+HAL_SimValueHandle HALSIM_GetSimValueHandle(HAL_SimDeviceHandle device,
+                                            const char* name) {
+  return SimSimDeviceData->GetValueHandle(device, name);
+}
+
+void HALSIM_EnumerateSimValues(HAL_SimDeviceHandle device, void* param,
+                               HALSIM_SimValueCallback callback) {
+  SimSimDeviceData->EnumerateValues(device, param, callback);
+}
+
+const char** HALSIM_GetSimValueEnumOptions(HAL_SimValueHandle handle,
+                                           int32_t* numOptions) {
+  return SimSimDeviceData->GetValueEnumOptions(handle, numOptions);
+}
+
+void HALSIM_ResetSimDeviceData(void) { SimSimDeviceData->ResetData(); }
+
+}  // extern "C"
diff --git a/hal/src/main/native/sim/mockdata/SimDeviceDataInternal.h b/hal/src/main/native/sim/mockdata/SimDeviceDataInternal.h
new file mode 100644
index 0000000..2582eca
--- /dev/null
+++ b/hal/src/main/native/sim/mockdata/SimDeviceDataInternal.h
@@ -0,0 +1,214 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <memory>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include <wpi/StringMap.h>
+#include <wpi/UidVector.h>
+#include <wpi/spinlock.h>
+
+#include "hal/Value.h"
+#include "mockdata/SimCallbackRegistry.h"
+#include "mockdata/SimDeviceData.h"
+
+namespace hal {
+
+namespace impl {
+
+template <typename CallbackFunction>
+class SimUnnamedCallbackRegistry {
+ public:
+  using RawFunctor = void (*)();
+
+ protected:
+  using CallbackVector = wpi::UidVector<HalCallbackListener<RawFunctor>, 4>;
+
+ public:
+  void Cancel(int32_t uid) {
+    if (m_callbacks) m_callbacks->erase(uid - 1);
+  }
+
+  void Reset() {
+    if (m_callbacks) m_callbacks->clear();
+  }
+
+  int32_t Register(CallbackFunction callback, void* param) {
+    // Must return -1 on a null callback for error handling
+    if (callback == nullptr) return -1;
+    if (!m_callbacks) m_callbacks = std::make_unique<CallbackVector>();
+    return m_callbacks->emplace_back(param,
+                                     reinterpret_cast<RawFunctor>(callback)) +
+           1;
+  }
+
+  template <typename... U>
+  void Invoke(const char* name, U&&... u) const {
+    if (m_callbacks) {
+      for (auto&& cb : *m_callbacks) {
+        reinterpret_cast<CallbackFunction>(cb.callback)(name, cb.param,
+                                                        std::forward<U>(u)...);
+      }
+    }
+  }
+
+  template <typename... U>
+  LLVM_ATTRIBUTE_ALWAYS_INLINE void operator()(U&&... u) const {
+    return Invoke(std::forward<U>(u)...);
+  }
+
+ private:
+  std::unique_ptr<CallbackVector> m_callbacks;
+};
+
+template <typename CallbackFunction>
+class SimPrefixCallbackRegistry {
+  struct CallbackData {
+    CallbackData() = default;
+    CallbackData(const char* prefix_, void* param_, CallbackFunction callback_)
+        : prefix{prefix_}, callback{callback_}, param{param_} {}
+    std::string prefix;
+    CallbackFunction callback;
+    void* param;
+
+    explicit operator bool() const { return callback != nullptr; }
+  };
+  using CallbackVector = wpi::UidVector<CallbackData, 4>;
+
+ public:
+  void Cancel(int32_t uid) {
+    if (m_callbacks) m_callbacks->erase(uid - 1);
+  }
+
+  void Reset() {
+    if (m_callbacks) m_callbacks->clear();
+  }
+
+  int32_t Register(const char* prefix, void* param, CallbackFunction callback) {
+    // Must return -1 on a null callback for error handling
+    if (callback == nullptr) return -1;
+    if (!m_callbacks) m_callbacks = std::make_unique<CallbackVector>();
+    return m_callbacks->emplace_back(prefix, param, callback) + 1;
+  }
+
+  template <typename... U>
+  void Invoke(const char* name, U&&... u) const {
+    if (m_callbacks) {
+      for (auto&& cb : *m_callbacks) {
+        if (wpi::StringRef{name}.startswith(cb.prefix)) {
+          cb.callback(name, cb.param, std::forward<U>(u)...);
+        }
+      }
+    }
+  }
+
+  template <typename... U>
+  LLVM_ATTRIBUTE_ALWAYS_INLINE void operator()(U&&... u) const {
+    return Invoke(std::forward<U>(u)...);
+  }
+
+ private:
+  std::unique_ptr<CallbackVector> m_callbacks;
+};
+
+}  // namespace impl
+
+class SimDeviceData {
+ private:
+  struct Value {
+    Value(const char* name_, bool readonly_, const HAL_Value& value_)
+        : name{name_}, readonly{readonly_}, value{value_} {}
+
+    HAL_SimValueHandle handle{0};
+    std::string name;
+    bool readonly;
+    HAL_Value value;
+    std::vector<std::string> enumOptions;
+    std::vector<const char*> cstrEnumOptions;
+    impl::SimUnnamedCallbackRegistry<HALSIM_SimValueCallback> changed;
+  };
+
+  struct Device {
+    explicit Device(const char* name_) : name{name_} {}
+
+    HAL_SimDeviceHandle handle{0};
+    std::string name;
+    wpi::UidVector<std::unique_ptr<Value>, 16> values;
+    wpi::StringMap<Value*> valueMap;
+    impl::SimUnnamedCallbackRegistry<HALSIM_SimValueCallback> valueCreated;
+  };
+
+  wpi::UidVector<std::shared_ptr<Device>, 4> m_devices;
+  wpi::StringMap<std::weak_ptr<Device>> m_deviceMap;
+
+  wpi::recursive_spinlock m_mutex;
+
+  impl::SimPrefixCallbackRegistry<HALSIM_SimDeviceCallback> m_deviceCreated;
+  impl::SimPrefixCallbackRegistry<HALSIM_SimDeviceCallback> m_deviceFreed;
+
+  // call with lock held, returns null if does not exist
+  Device* LookupDevice(HAL_SimDeviceHandle handle);
+  Value* LookupValue(HAL_SimValueHandle handle);
+
+ public:
+  HAL_SimDeviceHandle CreateDevice(const char* name);
+  void FreeDevice(HAL_SimDeviceHandle handle);
+  HAL_SimValueHandle CreateValue(HAL_SimDeviceHandle device, const char* name,
+                                 bool readonly, int32_t numOptions,
+                                 const char** options,
+                                 const HAL_Value& initialValue);
+  HAL_Value GetValue(HAL_SimValueHandle handle);
+  void SetValue(HAL_SimValueHandle handle, const HAL_Value& value);
+
+  int32_t RegisterDeviceCreatedCallback(const char* prefix, void* param,
+                                        HALSIM_SimDeviceCallback callback,
+                                        bool initialNotify);
+
+  void CancelDeviceCreatedCallback(int32_t uid);
+
+  int32_t RegisterDeviceFreedCallback(const char* prefix, void* param,
+                                      HALSIM_SimDeviceCallback callback);
+
+  void CancelDeviceFreedCallback(int32_t uid);
+
+  HAL_SimDeviceHandle GetDeviceHandle(const char* name);
+  const char* GetDeviceName(HAL_SimDeviceHandle handle);
+
+  void EnumerateDevices(const char* prefix, void* param,
+                        HALSIM_SimDeviceCallback callback);
+
+  int32_t RegisterValueCreatedCallback(HAL_SimDeviceHandle device, void* param,
+                                       HALSIM_SimValueCallback callback,
+                                       bool initialNotify);
+
+  void CancelValueCreatedCallback(int32_t uid);
+
+  int32_t RegisterValueChangedCallback(HAL_SimValueHandle handle, void* param,
+                                       HALSIM_SimValueCallback callback,
+                                       bool initialNotify);
+
+  void CancelValueChangedCallback(int32_t uid);
+
+  HAL_SimValueHandle GetValueHandle(HAL_SimDeviceHandle device,
+                                    const char* name);
+
+  void EnumerateValues(HAL_SimDeviceHandle device, void* param,
+                       HALSIM_SimValueCallback callback);
+
+  const char** GetValueEnumOptions(HAL_SimValueHandle handle,
+                                   int32_t* numOptions);
+
+  void ResetData();
+};
+extern SimDeviceData* SimSimDeviceData;
+}  // namespace hal