Squashed 'third_party/allwpilib/' changes from f1a82828fe..ce550705d7

ce550705d7 [ntcore] Fix client "received unknown id -1" (#6186)
3989617bde [ntcore] NetworkTable::GetStruct: Add I template param (#6183)
f1836e1321 [fieldImages] Fix 2024 field json (#6179)
d05f179a9a [build] Fix running apriltagsvision Java example (#6173)
b1b03bed85 [wpilib] Update MotorControllerGroup deprecation message (#6171)
fa63fbf446 LICENSE.md: Bump year to 2024 (#6169)
4809f3d0fc [apriltag] Add 2024 AprilTag locations (#6168)
dd90965362 [wpiutil] Fix RawFrame.setInfo() NPE (#6167)
8659372d08 [fieldImages] Add 2024 field image (#6166)
a2e4d0b15d [docs] Fix docs for SysID routine (#6164)
0a46a3a618 [wpilib] Make ADXL345 default I2C address public (#6163)
7c26bc70ab [sysid] Load DataLog files directly for analysis (#6103)
f94e3d81b9 [docs] Fix SysId routine JavaDoc warnings (#6159)
6bed82a18e [wpilibc] Clean up C++ SysId routine (#6160)
4595f84719 [wpilib] Report LiveWindow-enabled-in-test (#6158)
707cb06105 [wpilib] Add SysIdRoutine logging utility and command factory (#6033)
3e40b9e5da [wpilib] Correct SmartDashboard usage reporting (#6157)
106518c3f8 [docs] Fix wpilibj JavaDoc warnings (#6154)
19cb2a8eb4 [wpilibj] Make class variables private to match C++ (#6153)
13f4460e00 [docs] Add missing docs to enum fields (NFC) (#6150)
4210f5635d [docs] Fix warnings about undocumented default constructors (#6151)
0f060afb55 [ntcore] Disable WebSocket fragmentation (#6149)
f29a7d2e50 [docs] Add missing JavaDocs (#6146)
6e58db398d [commands] Make Java fields private (#6148)
4ac0720385 [build] Clean up CMake files (#6141)
44db3e0ac0 [sysid] Make constexpr variables outside class scope inline (#6145)
73c7d87db7 [glass] NTStringChooser: Properly set retained (#6144)
25636b712f [build] Remove unnecessary native dependencies in wpilibjExamples (#6143)
01fb98baaa [docs] Add Missing JNI docs from C++ (NFC) (#6139)
5c424248c4 [wpilibj] Remove unused AnalogTriggerException (#6142)
c486972c55 [wpimath] Make ExponentialProfile.State mutable (#6138)
783acb9b72 [wpilibj] Store long preferences as integers (#6136)
99ab836894 [wpiutil] Add missing JavaDocs (NFC) (#6132)
ad0859a8c9 [docs] Add missing JavaDocs (#6125)
5579219716 [docs] Exclude quickbuf files and proto/struct packages from doclint (#6128)
98f06911c7 [sysid] Use eigenvector component instead of eigenvalue for fit quality check (#6131)
e1d49b975c [wpimath] Add LinearFilter reset() overload to initialize input and output buffers (#6133)
8a0bf2b7a4 [hal] Add CANAPITypes to java (#6121)
91d8837c11 [wpilib] Make protected fields in accelerometers/gyros private (#6134)
e7c9f27683 [wpilib] Add functional interface equivalents to MotorController (#6053)
8aca706217 [glass] Add type information to SmartDashboard menu (#6117)
7d3e4ddba9 [docs] Add warning about using user button to docs (NFC) (#6129)
ec3cb3dcba [build] Disable clang-tidy warning about test case names (#6127)
495585b25d [examples] Update april tag family to 36h11 (#6126)
f9aabc5ab2 [wpilib] Throw early when EventLoop is modified while running (#6115)
c16946c0ec [hal] Add CANJNI docs (NFC) (#6120)
b7f4eb2811 [doc] Update maven artifacts for units and apriltags (NFC) (#6123)
f419a62b38 [doc] Update maintainers.md (NFC) (#6124)
938bf45fd9 [wpiutil] Remove type param from ProtobufSerializable and StructSerializable (#6122)
c34debe012 [docs] Link to external OpenCV docs (#6119)
07183765de [hal] Fix formatting of HAL_ENUM enums (NFC) (#6114)
af46034b7f [wpilib] Document only first party controllers are guaranteed to have correct mapping (#6112)
636ef58d94 [hal] Properly error check readCANStreamSession (#6108)
cc631d2a69 [build] Fix generated source set location in the HAL (#6113)
09f76b32c2 [wpimath] Compile with UTF-8 encoding (#6111)
47c5fd8620 [sysid] Check data quality before OLS (#6110)
24a76be694 [hal] Add method to detect if the CAN Stream has overflowed (#6105)
9333951736 [hal] Allocate CANStreamMessage in JNI if null (#6107)
6a2d3c30a6 [wpiutil] Struct: Add info template parameter pack (#6086)
e07de37e64 [commands] Mark ParallelDeadlineGroup.setDeadline() final (#6102)
141241d2d6 [wpilib] Fix usage reporting for static classes (#6090)
f2c2bab7dc [sysid] Fix adjusted R² calculation (#6101)
5659038443 [wpiutil,cscore,apriltag] Fix RawFrame (#6098)
8aeee03626 [commands] Improve error message when composing commands twice in same composition (#6091)
55508706ff [wpiutil,cscore] Move VideoMode.PixelFormat to wpiutil (#6097)
ab78b930e9 [wpilib] ADIS16470: Add access to all 3 axes (#6074)
795d4be9fd [wpilib] Fix precision issue in Color round-and-clamp (#6100)
7aa9ad44b8 [commands] Deprecate C++ TransferOwnership() (#6095)
92c81d0791 [ci] Update pregenerate workflow to actions/checkout@v4 (#6094)
1ce617be07 [ci] Update artifact actions to v4 (#6092)
2441b57156 [wpilib] Add PWMSparkFlex MotorController (#6089)
21d1972d7a [wpiutil] DataLog: Ensure file is written on shutdown (#6087)
c29e8c66cf [wpiutil] DataLog: Fix UB in AppendImpl (#6088)
ab309e34ef [glass] Fix order of loading window settings (#6056)
22a322c9f3 [wpimath] Report error on negative PID gains (#6055)
1dba26c937 [wpilib] Add method to get breaker fault at a specific channel in PowerDistribution[Sticky]Faults (#5521)
ef1cb3f41e [commands] Fix compose-while-scheduled issue and test all compositions (#5581)
aeb1a4aa33 [wpiutil] Add serializable marker interfaces (#6060)
c1178d5add [wpilib] Add StadiaController and command wrapper (#6083)
4e4a468d4d [wpimath] Make feedforward classes throw exceptions for negative Kv or Ka (#6084)
d1793f077d [build] cmake: Add NO_WERROR option to disable -Werror (#6071)
43fb6e9f87 [glass] Add Profiled PID controller support & IZone Support (#5959)
bcef6c5398 [apriltag] Fix Java generation functions (#6063)
4059e0cd9f [hal,wpilib] Add function to control "Radio" LED (#6073)
0b2cfb3abc [dlt] Change datalogtool default folder to logs folder (#6079)
df5e439b0c [wpilib] PS4Controller: enable usage reporting (#6081)
0ff7478968 [cscore] Fix RawFrame class not being loaded in JNI (#6077)
6f23d32fe1 [wpilib] AddressableLED: Update warning about single driver (NFC) (#6069)
35a1c52788 [build] Upgrade quickbuf to 1.3.3 (#6072)
e4e2bafdb1 [sysid] Document timestamp units (#6065)
3d201c71f7 [ntcore] Fix overlapping subscriber handling (#6067)
f02984159f [glass] Check for null entries when updating struct/proto (#6059)
a004c9e05f [commands] SubsystemBase: allow setting name in constructor (#6052)
0b4c6a1546 [wpimath] Add more docs to SimulatedAnnealing (NFC) (#6054)
ab15dae887 [wpilib] ArcadeDrive: Fix max output handling (#6051)
9599c1f56f [hal] Add usage reporting ids from 2024v2 image (#6041)
f87c64af8a [wpimath] MecanumDriveWheelSpeeds: Fix desaturate() (#6040)
8798700cec [wpilibcExamples] Add inline specifier to constexpr constants (#6049)
85c9ae6eff [wpilib] Fix PS5 Controller mappings (#6050)
7c8b7a97ad [wpiutil] Zero out roborio system timestamp (#6042)
d9b504bc84 [wpilib] DataLogManager: Change sim location to logs subdir (#6039)
906b810136 [build] cmake: Fix ntcore generated header install (#6038)
56e5b404d1 Update to final 2024 V2 image (#6034)
8723ee5c39 [ntcore] Add cached topic property (#5494)
192a28af47 Fix JDK 21 warnings (#6028)
d40bdd70ba [build] Upgrade to spotbugs Gradle plugin 6.0.2 (#6027)
7bfadf32e5 [wpilibj] Joystick: make remainder of get axis methods final (#6024)
a770110438 [commands] CommandCompositionError: Include stacktrace of original composition (#5984)
54a55b8b53 [wpiutil,hal] Update image; init Rio Now() HMB with a FPGA session (#6016)
7d4e515a6b [wpimath] Simplify calculation of C for DARE precondition (#6022)
5200316c14 [ntcore] Update transmit period on topic add/remove (#6021)
ddf79a25d4 [wpiunits] Overload Measure.per(Time) to return Measure<Velocity> (#6018)
a71adef316 [wpiutil] Clean up circular_buffer iterator syntax (#6020)
39a0bf4b98 [examples] Call resetOdometry() when controller command is executed (#5905)
f5fc101fda [build] cmake: Export jars and clean up jar installs (#6014)
38bf024c96 [build] Update to Gradle 8.5 (#6007)
9d11544c18 [wpimath] Rotate traveling salesman solution so input and solution have same initial pose (#6015)
28deba20f5 [wpimath] Commit generated quickbuf Java files (#5994)
c2971c0bb3 [build] cmake: Export apriltag and wpimath (#6012)
41cfc961e4 gitattributes: Add linguist-generated locations (#6004)
14c3ade155 [wpimath] Struct cleanup (#6011)
90757b9e90 [wpilib] Make Color::HexString() constexpr (#5985)
2676b77873 Fix compilation issues that occur when building with bazel (#6008)
d32c10487c [examples] Update C++ examples to use CommandPtr (#5988)
9bc5fcf886 [build] cmake: Default WITH_JAVA_SOURCE to WITH_JAVA (#6005)
d431abba3b [upstream_utils] Fix GCEM namespace usage and add hypot(x, y, z) (#6002)
2bb1409b82 Clean up Java style (#5990)
66172ab288 Remove submodule (#6003)
e8f8c0ceb0 [upstream_utils] Update to latest Eigen HEAD (#5996)
890992a849 [hal] Commit generated usage reporting files (#5993)
a583ca01e1 [wpiutil] Change Struct to allow non-constexpr implementation (#5992)
ca272de400 [build] Fix Gradle compile_commands.json and clang-tidy warnings (#5977)
76ae090570 [wpiutil] type_traits: Add is_constexpr() (#5997)
5172ab8fd0 [commands] C++ CommandPtr: Prevent null initialization (#5991)
96914143ba [build] Bump native-utils to fix compile_commands.json (#5989)
464e6121ef [ci] Report failed status to Azure on failed tests (#2654)
5dad46cd45 [wpimath] Commit generated files (#5986)
54ab65a63a [ntcore] Commit generated files (#5962)
7ed900ae3a [wpilib] Add hex string constructor to Color and Color8Bit (#5063)
74b85b76a9 [wpimath] Make gcem call std functions if not constant-evaluated (#5983)
30816111db [wpimath] Fix TimeInterpolatableBuffer crash (#5972)
5cc923de33 [wpilib] DataLogManager: Use logs subdirectory on USB drives (#5975)
1144115da0 [commands] Add GetName to Subsystem, use in Scheduler tracer epochs (#5836)
ac7d726ac3 [wpimath] Add simulated annealing (#5961)
e09be72ee0 [wpimath] Remove unused SimpleMatrixUtils class (#5979)
0f9ebe92d9 [wpimath] Add generic circular buffer class to Java (#5969)
9fa28eb07a [ci] Bump actions/checkout to v4 (#5736)
ca684ac207 [hal] Add capability to read power distribution data as a stream (#4983)
51eecef2bd [wpimath] Optimize 2nd derivative of quintic splines (#3292)
4fcf0b25a1 [build] Apply a formatter for CMake files (#5973)
9b8011aa67 [build] Pin wpiformat version (#5982)
e00a0e84c1 [build] cmake: fix protobuf dependency finding for certain distributions (#5981)
23dd591394 [upstream_utils] Remove libuv patch that adjusts whitespace (#5976)
b0719942f0 [wpiutil] Timestamp: Report errors on Rio HMB init failure (#5974)
7bc89c4322 [wpilib] Update getAlliance() docs (NFC) (#5971)
841ea682d1 [upstream_utils] Upgrade to LLVM 17.0.5 (#5970)
a74db52dae [cameraserver] Add getVideo() pixelFormat overload (#5966)
a7eb422662 [build] Update native utils for new compile commands files (#5968)
544b231d4d [sysid] Add missing cassert include (#5967)
31cd015970 [wpimath] Add SysId doc links to LinearSystemId in C++ (NFC) (#5960)
9280054eab Revert "[build] Export wpimath protobuf symbols (#5952)"
2aba97c610 Export pb files from wpimath
c80b2d2017 [build] Export wpimath protobuf symbols (#5952)
3c0652c18a [cscore] Replace CS_PixelFormat with WPI_PixelFormat (#5954)
95716eb0cb [wpiunits] Documentation improvements (#5932)
423fd75fa8 [wpilib] Default LiveWindowEnabledInTest to false (#5950)
dfdea9c992 [wpimath] Make KalmanFilter variant for asymmetric updates (#5951)
ca81ced409 [wpiutil] Move RawFrame to wpiutil; add generation of RawFrame for AprilTags (#5923)
437cc91af5 [cscore] CvSink: Allow specifying output PixelFormat (#5943)
25b7dca46b [build] Remove CMake flat install option (#5944)
bb05e20247 [wpimath] Add protobuf/struct for trivial types (#5935)
35744a036e [wpimath] Move struct/proto classes to separate files (#5918)
80d7ad58ea [build] Declare platform launcher dependency explicitly (#5909)
f8d983b154 [ntcore] Protobuf/Struct: Use atomic_bool instead of atomic_flag (#5946)
4a44210ee3 [ntcore] NetworkTableInstance: Suppress unused lambda capture warning (#5947)
bdc8620d55 [upstream_utils] Fix fmt compilation errors on Windows (#5948)
0ca1e9b5f9 [wpimath] Add basic wpiunits support (#5821)
cc30824409 [ntcore] Increase client meta-topic decoding limit (#5934)
b1fad062f7 [wpilib] Use RKDP in DifferentialDrivetrainSim (#5931)
ead9ae5a69 [build] Add generateProto dependency to test and dev (#5933)
cfbff32185 [wpiutil] timestamp: Fix startup race on Rio (#5930)
7d90d0bcc3 [wpimath] Clean up StateSpaceUtil (#5891)
7755e45aac [build] Add generated protobuf headers to C++ test include path (#5926)
3985c031da [ntcore] ProtobufSubscriber: Fix typos (#5928)
7a87fe4b60 [ntcore] ProtobufSubscriber: Make mutex and msg mutable (#5927)
09f3ed6a5f [commands] Add static Trigger factories for robot mode changes (#5902)
79dd795bc0 [wpimath] Clean up VecBuilder and MatBuilder (#5906)
e117274a67 [wpilib] Change default Rio log dir from /home/lvuser to /home/lvuser/logs (#5899)
a8b80ca256 [upstream_utils] Update to libuv 1.47.0 (#5889)
b3a9c3e96b [build] Bump macOS deployment target to 12 (#5890)
0f8129677b [build] Distribute wpimath protobuf headers (#5925)
d105f9e3e9 [wpiutil] ProtobufBuffer: Fix buffer reallocation (#5924)
c5f2f6a0fb [fieldImages] Fix typo in field images artifact name (#5922)
c1a57e422a [commands] Clean up make_vector.h (#5917)
78ebc6e9ec [wpimath] change G to gearing in LinearSystemId factories (#5834)
9ada181866 [hal] DriverStation.h: Add stddef.h include (#5897)
95fa5ec72f [wpilibc,ntcoreffi] DataLogManager: join on Stop() call (#5910)
b6f2d3cc14 [build] Remove usage of Version.parse (#5911)
cc2cbeb04c [examples] Replace gyro rotation with poseEstimator rotation (#5900)
fa6b171e1c [wpiutil] Suppress protobuf warning false positives on GCC 13 (#5907)
d504639bbe [apriltag] Improve AprilTag docs (#5895)
3a1194be40 Replace static_cast<void>() with [[maybe_unused]] attribute (#5892)
70392cbbcb [build] cmake: Add protobuf dependency to wpiutil-config (#5886)
17c1bd5a83 [ntcore] Use json_fwd (#5881)
e69a9efeba [wpilibcExamples] Match array parameter bounds (#5880)
14dcd0d26f Use char instead of uint8_t for json::parse (#5877)
ec1d261984 [hal] Fix garbage data for match info before DS connection (#5879)
63dbf5c614 [wpiutil] MemoryBuffer: Fix normal read and file type check (#5875)
b2e7be9250 [ntcore] Only datalog meta-topics if specifically requested (#5873)
201a42a3cd [wpimath] Reorder TrapezoidProfile.calculate() arguments (#5874)
04a781b4d7 [apriltag] Add GetTags to C++ version of AprilTagFieldLayout (#5872)
87a8a1ced4 [docs] Exclude eigen and protobuf from doxygen (#5871)

git-subtree-dir: third_party/allwpilib
git-subtree-split: ce550705d7cdab117c0153a202973fc026a81274
Signed-off-by: Maxwell Henderson <mxwhenderson@gmail.com>
Change-Id: Ic8645d0551d62b411b0a816c493f0f33291896a1
diff --git a/hal/src/main/native/athena/CANAPI.cpp b/hal/src/main/native/athena/CANAPI.cpp
index 70f09e0..40332ef 100644
--- a/hal/src/main/native/athena/CANAPI.cpp
+++ b/hal/src/main/native/athena/CANAPI.cpp
@@ -281,4 +281,19 @@
     }
   }
 }
+
+uint32_t HAL_StartCANStream(HAL_CANHandle handle, int32_t apiId, int32_t depth,
+                            int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  uint32_t messageId = CreateCANId(can.get(), apiId);
+
+  uint32_t session = 0;
+  HAL_CAN_OpenStreamSession(&session, messageId, 0x1FFFFFFF, depth, status);
+  return session;
+}
 }  // extern "C"
diff --git a/hal/src/main/native/athena/CTREPDP.cpp b/hal/src/main/native/athena/CTREPDP.cpp
index 1a25a64..21896ec 100644
--- a/hal/src/main/native/athena/CTREPDP.cpp
+++ b/hal/src/main/native/athena/CTREPDP.cpp
@@ -10,6 +10,7 @@
 #include "HALInitializer.h"
 #include "HALInternal.h"
 #include "PortsInternal.h"
+#include "hal/CAN.h"
 #include "hal/CANAPI.h"
 #include "hal/Errors.h"
 #include "hal/handles/IndexedHandleResource.h"
@@ -107,6 +108,8 @@
 struct PDP {
   HAL_CANHandle canHandle;
   std::string previousAllocation;
+  bool streamHandleAllocated{false};
+  uint32_t streamSessionHandles[3];
 };
 }  // namespace
 
@@ -523,4 +526,241 @@
   HAL_WriteCANPacket(pdp->canHandle, pdpControl, 1, Control1, status);
 }
 
+uint32_t HAL_StartCANStream(HAL_CANHandle handle, int32_t apiId, int32_t depth,
+                            int32_t* status);
+
+void HAL_StartPDPStream(HAL_PDPHandle handle, int32_t* status) {
+  auto pdp = pdpHandles->Get(handle);
+  if (pdp == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (pdp->streamHandleAllocated) {
+    *status = RESOURCE_IS_ALLOCATED;
+    return;
+  }
+
+  pdp->streamSessionHandles[0] =
+      HAL_StartCANStream(pdp->canHandle, Status1, 50, status);
+  if (*status != 0) {
+    return;
+  }
+  pdp->streamSessionHandles[1] =
+      HAL_StartCANStream(pdp->canHandle, Status2, 50, status);
+  if (*status != 0) {
+    HAL_CAN_CloseStreamSession(pdp->streamSessionHandles[0]);
+    return;
+  }
+  pdp->streamSessionHandles[2] =
+      HAL_StartCANStream(pdp->canHandle, Status3, 50, status);
+  if (*status != 0) {
+    HAL_CAN_CloseStreamSession(pdp->streamSessionHandles[0]);
+    HAL_CAN_CloseStreamSession(pdp->streamSessionHandles[1]);
+    return;
+  }
+  pdp->streamHandleAllocated = true;
+}
+
+HAL_PowerDistributionChannelData* HAL_GetPDPStreamData(HAL_PDPHandle handle,
+                                                       int32_t* count,
+                                                       int32_t* status) {
+  auto pdp = pdpHandles->Get(handle);
+  if (pdp == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return nullptr;
+  }
+
+  if (!pdp->streamHandleAllocated) {
+    *status = RESOURCE_OUT_OF_RANGE;
+    return nullptr;
+  }
+
+  *count = 0;
+  // 3 streams, 6 channels per stream, 50 depth per stream
+  HAL_PowerDistributionChannelData* retData =
+      new HAL_PowerDistributionChannelData[3 * 6 * 50];
+
+  HAL_CANStreamMessage messages[50];
+  uint32_t messagesRead = 0;
+  HAL_CAN_ReadStreamSession(pdp->streamSessionHandles[0], messages, 50,
+                            &messagesRead, status);
+  if (*status < 0) {
+    goto Exit;
+  }
+
+  for (uint32_t i = 0; i < messagesRead; i++) {
+    PdpStatus1 pdpStatus;
+    std::memcpy(pdpStatus.data, messages[i].data, sizeof(messages[i].data));
+    uint32_t timestamp = messages[i].timeStamp;
+
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan1_h8) << 2) |
+         pdpStatus.bits.chan1_l2) *
+        0.125;
+    retData[*count].channel = 1;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan2_h6) << 4) |
+         pdpStatus.bits.chan2_l4) *
+        0.125;
+    retData[*count].channel = 2;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan3_h4) << 6) |
+         pdpStatus.bits.chan3_l6) *
+        0.125;
+    retData[*count].channel = 3;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan4_h2) << 8) |
+         pdpStatus.bits.chan4_l8) *
+        0.125;
+    retData[*count].channel = 4;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan5_h8) << 2) |
+         pdpStatus.bits.chan5_l2) *
+        0.125;
+    retData[*count].channel = 5;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan6_h6) << 4) |
+         pdpStatus.bits.chan6_l4) *
+        0.125;
+    retData[*count].channel = 6;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+  }
+
+  messagesRead = 0;
+  HAL_CAN_ReadStreamSession(pdp->streamSessionHandles[1], messages, 50,
+                            &messagesRead, status);
+  if (*status < 0) {
+    goto Exit;
+  }
+
+  for (uint32_t i = 0; i < messagesRead; i++) {
+    PdpStatus2 pdpStatus;
+    std::memcpy(pdpStatus.data, messages[i].data, sizeof(messages[i].data));
+    uint32_t timestamp = messages[i].timeStamp;
+
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan7_h8) << 2) |
+         pdpStatus.bits.chan7_l2) *
+        0.125;
+    retData[*count].channel = 7;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan8_h6) << 4) |
+         pdpStatus.bits.chan8_l4) *
+        0.125;
+    retData[*count].channel = 8;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan9_h4) << 6) |
+         pdpStatus.bits.chan9_l6) *
+        0.125;
+    retData[*count].channel = 9;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan10_h2) << 8) |
+         pdpStatus.bits.chan10_l8) *
+        0.125;
+    retData[*count].channel = 10;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan11_h8) << 2) |
+         pdpStatus.bits.chan11_l2) *
+        0.125;
+    retData[*count].channel = 11;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan12_h6) << 4) |
+         pdpStatus.bits.chan12_l4) *
+        0.125;
+    retData[*count].channel = 12;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+  }
+
+  messagesRead = 0;
+  HAL_CAN_ReadStreamSession(pdp->streamSessionHandles[2], messages, 50,
+                            &messagesRead, status);
+  if (*status < 0) {
+    goto Exit;
+  }
+
+  for (uint32_t i = 0; i < messagesRead; i++) {
+    PdpStatus3 pdpStatus;
+    std::memcpy(pdpStatus.data, messages[i].data, sizeof(messages[i].data));
+    uint32_t timestamp = messages[i].timeStamp;
+
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan13_h8) << 2) |
+         pdpStatus.bits.chan13_l2) *
+        0.125;
+    retData[*count].channel = 13;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan14_h6) << 4) |
+         pdpStatus.bits.chan14_l4) *
+        0.125;
+    retData[*count].channel = 14;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan15_h4) << 6) |
+         pdpStatus.bits.chan15_l6) *
+        0.125;
+    retData[*count].channel = 15;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        ((static_cast<uint32_t>(pdpStatus.bits.chan16_h2) << 8) |
+         pdpStatus.bits.chan16_l8) *
+        0.125;
+    retData[*count].channel = 16;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+  }
+
+Exit:
+  if (*status < 0) {
+    delete[] retData;
+    retData = nullptr;
+  }
+  return retData;
+}
+
+void HAL_StopPDPStream(HAL_PDPHandle handle, int32_t* status) {
+  auto pdp = pdpHandles->Get(handle);
+  if (pdp == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (!pdp->streamHandleAllocated) {
+    *status = RESOURCE_OUT_OF_RANGE;
+    return;
+  }
+
+  HAL_CAN_CloseStreamSession(pdp->streamSessionHandles[0]);
+  HAL_CAN_CloseStreamSession(pdp->streamSessionHandles[1]);
+  HAL_CAN_CloseStreamSession(pdp->streamSessionHandles[2]);
+
+  pdp->streamHandleAllocated = false;
+}
+
 }  // extern "C"
diff --git a/hal/src/main/native/athena/CTREPDP.h b/hal/src/main/native/athena/CTREPDP.h
index dd4b298..99606e0 100644
--- a/hal/src/main/native/athena/CTREPDP.h
+++ b/hal/src/main/native/athena/CTREPDP.h
@@ -6,6 +6,7 @@
 
 #include <stdint.h>
 
+#include "hal/PowerDistribution.h"
 #include "hal/Types.h"
 
 /**
@@ -130,6 +131,15 @@
  * @param handle the module handle
  */
 void HAL_ClearPDPStickyFaults(HAL_PDPHandle handle, int32_t* status);
+
+void HAL_StartPDPStream(HAL_PDPHandle handle, int32_t* status);
+
+HAL_PowerDistributionChannelData* HAL_GetPDPStreamData(HAL_PDPHandle handle,
+                                                       int32_t* count,
+                                                       int32_t* status);
+
+void HAL_StopPDPStream(HAL_PDPHandle handle, int32_t* status);
+
 #ifdef __cplusplus
 }  // extern "C"
 #endif
diff --git a/hal/src/main/native/athena/FRCDriverStation.cpp b/hal/src/main/native/athena/FRCDriverStation.cpp
index 12739c8..c30fbb9 100644
--- a/hal/src/main/native/athena/FRCDriverStation.cpp
+++ b/hal/src/main/native/athena/FRCDriverStation.cpp
@@ -181,9 +181,10 @@
 namespace {
 struct TcpCache {
   TcpCache() { std::memset(this, 0, sizeof(*this)); }
-  void Update(uint32_t mask);
+  bool Update(uint32_t mask);
   void CloneTo(TcpCache* other) { std::memcpy(other, this, sizeof(*this)); }
 
+  bool hasReadMatchInfo = false;
   HAL_MatchInfo matchInfo;
   HAL_JoystickDescriptor descriptors[HAL_kMaxJoysticks];
 };
@@ -199,15 +200,25 @@
                                            kTcpRecvMask_MatchInfo |
                                            kTcpRecvMask_GameSpecific;
 
-void TcpCache::Update(uint32_t mask) {
+bool TcpCache::Update(uint32_t mask) {
+  bool failedToReadInfo = false;
   if ((mask & combinedMatchInfoMask) != 0) {
-    HAL_GetMatchInfoInternal(&matchInfo);
+    int status = HAL_GetMatchInfoInternal(&matchInfo);
+    if (status != 0) {
+      failedToReadInfo = true;
+      if (!hasReadMatchInfo) {
+        std::memset(&matchInfo, 0, sizeof(matchInfo));
+      }
+    } else {
+      hasReadMatchInfo = true;
+    }
   }
   for (int i = 0; i < HAL_kMaxJoysticks; i++) {
     if ((mask & (1 << i)) != 0) {
       HAL_GetJoystickDescriptorInternal(i, &descriptors[i]);
     }
   }
+  return failedToReadInfo;
 }
 
 namespace hal::init {
@@ -532,13 +543,21 @@
     if (controlWord.dsAttached) {
       newestControlWord = currentRead->controlWord;
     } else {
+      // Zero out the control word. When the DS has never been connected
+      // this returns garbage. And there is no way we can detect that.
+      std::memset(&controlWord, 0, sizeof(controlWord));
       newestControlWord = controlWord;
     }
   }
 
   uint32_t mask = tcpMask.exchange(0);
   if (mask != 0) {
-    tcpCache.Update(mask);
+    bool failedToReadMatchInfo = tcpCache.Update(mask);
+    if (failedToReadMatchInfo) {
+      // If we failed to read match info
+      // we want to try again next iteration
+      tcpMask.fetch_or(combinedMatchInfoMask);
+    }
     std::scoped_lock tcpLock(tcpCacheMutex);
     tcpCache.CloneTo(&tcpCurrent);
   }
diff --git a/hal/src/main/native/athena/HAL.cpp b/hal/src/main/native/athena/HAL.cpp
index d00bf9f..f239391 100644
--- a/hal/src/main/native/athena/HAL.cpp
+++ b/hal/src/main/native/athena/HAL.cpp
@@ -4,6 +4,7 @@
 
 #include "hal/HAL.h"
 
+#include <dlfcn.h>
 #include <signal.h>  // linux for kill
 #include <sys/prctl.h>
 #include <unistd.h>
@@ -82,6 +83,7 @@
   InitializeFRCDriverStation();
   InitializeI2C();
   InitializeInterrupts();
+  InitializeLEDs();
   InitializeMain();
   InitializeNotifier();
   InitializeCTREPDP();
@@ -522,6 +524,35 @@
   return true;
 }
 
+static void SetupNowRio(void) {
+  nFPGA::nRoboRIO_FPGANamespace::g_currentTargetClass =
+      nLoadOut::getTargetClass();
+
+  int32_t status = 0;
+
+  Dl_info info;
+  status = dladdr(reinterpret_cast<void*>(tHMB::create), &info);
+  if (status == 0) {
+    fmt::print(stderr, "Failed to call dladdr on chipobject {}\n", dlerror());
+    return;
+  }
+
+  void* chipObjectLibrary = dlopen(info.dli_fname, RTLD_LAZY);
+  if (chipObjectLibrary == nullptr) {
+    fmt::print(stderr, "Failed to call dlopen on chipobject {}\n", dlerror());
+    return;
+  }
+
+  std::unique_ptr<tHMB> hmb;
+  hmb.reset(tHMB::create(&status));
+  if (hmb == nullptr) {
+    fmt::print(stderr, "Failed to open HMB on chipobject {}\n", status);
+    dlclose(chipObjectLibrary);
+    return;
+  }
+  wpi::impl::SetupNowRio(chipObjectLibrary, std::move(hmb));
+}
+
 HAL_Bool HAL_Initialize(int32_t timeout, int32_t mode) {
   static std::atomic_bool initialized{false};
   static wpi::mutex initializeMutex;
@@ -562,14 +593,13 @@
     setNewDataSem(nullptr);
   });
 
-  // Setup WPI_Now to use FPGA timestamp
-  // this also sets nFPGA::nRoboRIO_FPGANamespace::g_currentTargetClass
-  wpi::impl::SetupNowRio();
+  SetupNowRio();
 
   int32_t status = 0;
 
   HAL_InitializeHMB(&status);
   if (status != 0) {
+    fmt::print(stderr, "Failed to open HAL HMB, status code {}\n", status);
     return false;
   }
   hmbBuffer = HAL_GetHMBBuffer();
diff --git a/hal/src/main/native/athena/HALInitializer.h b/hal/src/main/native/athena/HALInitializer.h
index 182ab5b..20b9a8b 100644
--- a/hal/src/main/native/athena/HALInitializer.h
+++ b/hal/src/main/native/athena/HALInitializer.h
@@ -40,6 +40,7 @@
 extern void InitializeHAL();
 extern void InitializeI2C();
 extern void InitializeInterrupts();
+extern void InitializeLEDs();
 extern void InitializeMain();
 extern void InitializeNotifier();
 extern void InitializeCTREPDP();
diff --git a/hal/src/main/native/athena/LEDs.cpp b/hal/src/main/native/athena/LEDs.cpp
new file mode 100644
index 0000000..8fa603e
--- /dev/null
+++ b/hal/src/main/native/athena/LEDs.cpp
@@ -0,0 +1,89 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "hal/LEDs.h"
+
+#include <unistd.h>
+
+#include <fstream>
+
+#include <wpi/fs.h>
+
+#include "hal/Errors.h"
+
+namespace hal::init {
+
+void InitializeLEDs() {
+  int32_t status = 0;
+  HAL_SetRadioLEDState(HAL_RadioLED_kOff, &status);
+}
+}  // namespace hal::init
+
+static const fs::path radioLEDGreenFilePath =
+    "/sys/class/leds/nilrt:wifi:primary/brightness";
+static const fs::path radioLEDRedFilePath =
+    "/sys/class/leds/nilrt:wifi:secondary/brightness";
+
+static const char* onStr = "1";
+static const char* offStr = "0";
+
+extern "C" {
+void HAL_SetRadioLEDState(HAL_RadioLEDState state, int32_t* status) {
+  std::error_code ec;
+  fs::file_t greenFile = fs::OpenFileForWrite(radioLEDGreenFilePath, ec,
+                                              fs::CD_OpenExisting, fs::OF_Text);
+  if (ec) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+  fs::file_t redFile = fs::OpenFileForWrite(radioLEDRedFilePath, ec,
+                                            fs::CD_OpenExisting, fs::OF_Text);
+  if (ec) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+
+  write(greenFile, state & HAL_RadioLED_kGreen ? onStr : offStr, 1);
+  write(redFile, state & HAL_RadioLED_kRed ? onStr : offStr, 1);
+
+  fs::CloseFile(greenFile);
+  fs::CloseFile(redFile);
+}
+
+bool ReadStateFromFile(fs::path path, int32_t* status) {
+  std::error_code ec;
+  fs::file_t file = fs::OpenFileForRead(path, ec, fs::OF_Text);
+  if (ec) {
+    *status = INCOMPATIBLE_STATE;
+    return false;
+  }
+  // We only need to read one byte because the file won't have leading zeros.
+  char buf[1]{};
+  size_t count = read(file, buf, 1);
+  if (count == 0) {
+    *status = INCOMPATIBLE_STATE;
+    return false;
+  }
+  // If the brightness is not zero, the LED is on.
+  return buf[0] != '0';
+}
+
+HAL_RadioLEDState HAL_GetRadioLEDState(int32_t* status) {
+  bool green = ReadStateFromFile(radioLEDGreenFilePath, status);
+  bool red = ReadStateFromFile(radioLEDRedFilePath, status);
+  if (*status == 0) {
+    if (green && red) {
+      return HAL_RadioLED_kOrange;
+    } else if (green) {
+      return HAL_RadioLED_kGreen;
+    } else if (red) {
+      return HAL_RadioLED_kRed;
+    } else {
+      return HAL_RadioLED_kOff;
+    }
+  } else {
+    return HAL_RadioLED_kOff;
+  }
+}
+}  // extern "C"
diff --git a/hal/src/main/native/athena/PowerDistribution.cpp b/hal/src/main/native/athena/PowerDistribution.cpp
index 0d2b963..580aa90 100644
--- a/hal/src/main/native/athena/PowerDistribution.cpp
+++ b/hal/src/main/native/athena/PowerDistribution.cpp
@@ -273,4 +273,36 @@
   }
 }
 
+void HAL_StartPowerDistributionStream(HAL_PowerDistributionHandle handle,
+                                      int32_t* status) {
+  if (IsCtre(handle)) {
+    HAL_StartPDPStream(handle, status);
+  } else {
+    HAL_StartREVPDHStream(handle, status);
+  }
+}
+
+HAL_PowerDistributionChannelData* HAL_GetPowerDistributionStreamData(
+    HAL_PowerDistributionHandle handle, int32_t* count, int32_t* status) {
+  if (IsCtre(handle)) {
+    return HAL_GetPDPStreamData(handle, count, status);
+  } else {
+    return HAL_GetREVPDHStreamData(handle, count, status);
+  }
+}
+
+void HAL_FreePowerDistributionStreamData(HAL_PowerDistributionChannelData* data,
+                                         int32_t count) {
+  delete[] data;
+}
+
+void HAL_StopPowerDistributionStream(HAL_PowerDistributionHandle handle,
+                                     int32_t* status) {
+  if (IsCtre(handle)) {
+    HAL_StopPDPStream(handle, status);
+  } else {
+    HAL_StopREVPDHStream(handle, status);
+  }
+}
+
 }  // extern "C"
diff --git a/hal/src/main/native/athena/REVPDH.cpp b/hal/src/main/native/athena/REVPDH.cpp
index 10c019d..3398404 100644
--- a/hal/src/main/native/athena/REVPDH.cpp
+++ b/hal/src/main/native/athena/REVPDH.cpp
@@ -4,6 +4,7 @@
 
 #include "REVPDH.h"
 
+#include <hal/CAN.h>
 #include <hal/CANAPI.h>
 #include <hal/CANAPITypes.h>
 #include <hal/Errors.h>
@@ -37,6 +38,8 @@
   HAL_CANHandle hcan;
   std::string previousAllocation;
   HAL_PowerDistributionVersion versionInfo;
+  bool streamHandleAllocated{false};
+  uint32_t streamSessionHandles[4];
 };
 
 }  // namespace
@@ -636,4 +639,271 @@
                      PDH_CLEAR_FAULTS_FRAME_API, status);
 }
 
+uint32_t HAL_StartCANStream(HAL_CANHandle handle, int32_t apiId, int32_t depth,
+                            int32_t* status);
+
+void HAL_StartREVPDHStream(HAL_REVPDHHandle handle, int32_t* status) {
+  auto hpdh = REVPDHHandles->Get(handle);
+  if (hpdh == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (hpdh->streamHandleAllocated) {
+    *status = RESOURCE_IS_ALLOCATED;
+    return;
+  }
+
+  hpdh->streamSessionHandles[0] =
+      HAL_StartCANStream(hpdh->hcan, PDH_STATUS_0_FRAME_API, 50, status);
+  if (*status != 0) {
+    return;
+  }
+  hpdh->streamSessionHandles[1] =
+      HAL_StartCANStream(hpdh->hcan, PDH_STATUS_1_FRAME_API, 50, status);
+  if (*status != 0) {
+    HAL_CAN_CloseStreamSession(hpdh->streamSessionHandles[0]);
+    return;
+  }
+  hpdh->streamSessionHandles[2] =
+      HAL_StartCANStream(hpdh->hcan, PDH_STATUS_2_FRAME_API, 50, status);
+  if (*status != 0) {
+    HAL_CAN_CloseStreamSession(hpdh->streamSessionHandles[0]);
+    HAL_CAN_CloseStreamSession(hpdh->streamSessionHandles[1]);
+    return;
+  }
+  hpdh->streamSessionHandles[3] =
+      HAL_StartCANStream(hpdh->hcan, PDH_STATUS_3_FRAME_API, 50, status);
+  if (*status != 0) {
+    HAL_CAN_CloseStreamSession(hpdh->streamSessionHandles[0]);
+    HAL_CAN_CloseStreamSession(hpdh->streamSessionHandles[1]);
+    HAL_CAN_CloseStreamSession(hpdh->streamSessionHandles[3]);
+    return;
+  }
+  hpdh->streamHandleAllocated = true;
+}
+
+HAL_PowerDistributionChannelData* HAL_GetREVPDHStreamData(
+    HAL_REVPDHHandle handle, int32_t* count, int32_t* status) {
+  auto hpdh = REVPDHHandles->Get(handle);
+  if (hpdh == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return nullptr;
+  }
+
+  if (!hpdh->streamHandleAllocated) {
+    *status = RESOURCE_OUT_OF_RANGE;
+    return nullptr;
+  }
+
+  *count = 0;
+  // 4 streams, 6 channels per stream, 50 depth per stream
+  HAL_PowerDistributionChannelData* retData =
+      new HAL_PowerDistributionChannelData[4 * 6 * 50];
+
+  HAL_CANStreamMessage messages[50];
+  uint32_t messagesRead = 0;
+  HAL_CAN_ReadStreamSession(hpdh->streamSessionHandles[0], messages, 50,
+                            &messagesRead, status);
+  if (*status < 0) {
+    goto Exit;
+  }
+
+  for (uint32_t i = 0; i < messagesRead; i++) {
+    PDH_status_0_t statusFrame0;
+    PDH_status_0_unpack(&statusFrame0, messages[i].data, PDH_STATUS_0_LENGTH);
+    uint32_t timestamp = messages[i].timeStamp;
+
+    retData[*count].current =
+        PDH_status_0_channel_0_current_decode(statusFrame0.channel_0_current);
+    retData[*count].channel = 1;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_0_channel_1_current_decode(statusFrame0.channel_1_current);
+    retData[*count].channel = 2;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_0_channel_2_current_decode(statusFrame0.channel_2_current);
+    retData[*count].channel = 3;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_0_channel_3_current_decode(statusFrame0.channel_3_current);
+    retData[*count].channel = 4;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_0_channel_4_current_decode(statusFrame0.channel_4_current);
+    retData[*count].channel = 5;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_0_channel_5_current_decode(statusFrame0.channel_5_current);
+    retData[*count].channel = 6;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+  }
+
+  messagesRead = 0;
+  HAL_CAN_ReadStreamSession(hpdh->streamSessionHandles[1], messages, 50,
+                            &messagesRead, status);
+  if (*status < 0) {
+    goto Exit;
+  }
+
+  for (uint32_t i = 0; i < messagesRead; i++) {
+    PDH_status_1_t statusFrame1;
+    PDH_status_1_unpack(&statusFrame1, messages[i].data, PDH_STATUS_1_LENGTH);
+    uint32_t timestamp = messages[i].timeStamp;
+
+    retData[*count].current =
+        PDH_status_1_channel_6_current_decode(statusFrame1.channel_6_current);
+    retData[*count].channel = 7;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_1_channel_7_current_decode(statusFrame1.channel_7_current);
+    retData[*count].channel = 8;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_1_channel_8_current_decode(statusFrame1.channel_8_current);
+    retData[*count].channel = 9;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_1_channel_9_current_decode(statusFrame1.channel_9_current);
+    retData[*count].channel = 10;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_1_channel_10_current_decode(statusFrame1.channel_10_current);
+    retData[*count].channel = 11;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_1_channel_11_current_decode(statusFrame1.channel_11_current);
+    retData[*count].channel = 12;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+  }
+
+  messagesRead = 0;
+  HAL_CAN_ReadStreamSession(hpdh->streamSessionHandles[2], messages, 50,
+                            &messagesRead, status);
+  if (*status < 0) {
+    goto Exit;
+  }
+
+  for (uint32_t i = 0; i < messagesRead; i++) {
+    PDH_status_2_t statusFrame2;
+    PDH_status_2_unpack(&statusFrame2, messages[i].data, PDH_STATUS_2_LENGTH);
+    uint32_t timestamp = messages[i].timeStamp;
+
+    retData[*count].current =
+        PDH_status_2_channel_12_current_decode(statusFrame2.channel_12_current);
+    retData[*count].channel = 13;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_2_channel_13_current_decode(statusFrame2.channel_13_current);
+    retData[*count].channel = 14;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_2_channel_14_current_decode(statusFrame2.channel_14_current);
+    retData[*count].channel = 15;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_2_channel_15_current_decode(statusFrame2.channel_15_current);
+    retData[*count].channel = 16;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_2_channel_16_current_decode(statusFrame2.channel_16_current);
+    retData[*count].channel = 17;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_2_channel_17_current_decode(statusFrame2.channel_17_current);
+    retData[*count].channel = 18;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+  }
+
+  messagesRead = 0;
+  HAL_CAN_ReadStreamSession(hpdh->streamSessionHandles[3], messages, 50,
+                            &messagesRead, status);
+  if (*status < 0) {
+    goto Exit;
+  }
+
+  for (uint32_t i = 0; i < messagesRead; i++) {
+    PDH_status_3_t statusFrame3;
+    PDH_status_3_unpack(&statusFrame3, messages[i].data, PDH_STATUS_3_LENGTH);
+    uint32_t timestamp = messages[i].timeStamp;
+
+    retData[*count].current =
+        PDH_status_3_channel_18_current_decode(statusFrame3.channel_18_current);
+    retData[*count].channel = 19;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_3_channel_19_current_decode(statusFrame3.channel_19_current);
+    retData[*count].channel = 20;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_3_channel_20_current_decode(statusFrame3.channel_20_current);
+    retData[*count].channel = 21;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_3_channel_21_current_decode(statusFrame3.channel_21_current);
+    retData[*count].channel = 22;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_3_channel_22_current_decode(statusFrame3.channel_22_current);
+    retData[*count].channel = 23;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+    retData[*count].current =
+        PDH_status_3_channel_23_current_decode(statusFrame3.channel_23_current);
+    retData[*count].channel = 24;
+    retData[*count].timestamp = timestamp;
+    (*count)++;
+  }
+
+Exit:
+  if (*status < 0) {
+    delete[] retData;
+    retData = nullptr;
+  }
+  return retData;
+}
+
+void HAL_StopREVPDHStream(HAL_REVPDHHandle handle, int32_t* status) {
+  auto hpdh = REVPDHHandles->Get(handle);
+  if (hpdh == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (!hpdh->streamHandleAllocated) {
+    *status = RESOURCE_OUT_OF_RANGE;
+    return;
+  }
+
+  HAL_CAN_CloseStreamSession(hpdh->streamSessionHandles[0]);
+  HAL_CAN_CloseStreamSession(hpdh->streamSessionHandles[1]);
+  HAL_CAN_CloseStreamSession(hpdh->streamSessionHandles[2]);
+  HAL_CAN_CloseStreamSession(hpdh->streamSessionHandles[3]);
+
+  hpdh->streamHandleAllocated = false;
+}
+
 }  // extern "C"
diff --git a/hal/src/main/native/athena/REVPDH.h b/hal/src/main/native/athena/REVPDH.h
index d0b10f2..0046455 100644
--- a/hal/src/main/native/athena/REVPDH.h
+++ b/hal/src/main/native/athena/REVPDH.h
@@ -158,6 +158,13 @@
  */
 void HAL_ClearREVPDHStickyFaults(HAL_REVPDHHandle handle, int32_t* status);
 
+void HAL_StartREVPDHStream(HAL_REVPDHHandle handle, int32_t* status);
+
+HAL_PowerDistributionChannelData* HAL_GetREVPDHStreamData(
+    HAL_REVPDHHandle handle, int32_t* count, int32_t* status);
+
+void HAL_StopREVPDHStream(HAL_REVPDHHandle handle, int32_t* status);
+
 #ifdef __cplusplus
 }  // extern "C"
 #endif
diff --git a/hal/src/main/native/athena/mockdata/RoboRioData.cpp b/hal/src/main/native/athena/mockdata/RoboRioData.cpp
index 8559394..b57b706 100644
--- a/hal/src/main/native/athena/mockdata/RoboRioData.cpp
+++ b/hal/src/main/native/athena/mockdata/RoboRioData.cpp
@@ -30,6 +30,7 @@
 DEFINE_CAPI(double, BrownoutVoltage, 6.75)
 DEFINE_CAPI(double, CPUTemp, 45.0)
 DEFINE_CAPI(int32_t, TeamNumber, 0)
+DEFINE_CAPI(HAL_RadioLEDState, RadioLEDState, HAL_RadioLED_kOff);
 
 int32_t HALSIM_RegisterRoboRioSerialNumberCallback(
     HAL_RoboRioStringCallback callback, void* param, HAL_Bool initialNotify) {
diff --git a/hal/src/main/native/cpp/jni/CANJNI.cpp b/hal/src/main/native/cpp/jni/CANJNI.cpp
index 9375a06..40838d3 100644
--- a/hal/src/main/native/cpp/jni/CANJNI.cpp
+++ b/hal/src/main/native/cpp/jni/CANJNI.cpp
@@ -135,6 +135,17 @@
   (JNIEnv* env, jclass, jint sessionHandle, jobjectArray messages,
    jint messagesToRead)
 {
+  if (messages == nullptr) {
+    ThrowNullPointerException(env, "messages cannot be null");
+    return 0;
+  }
+
+  jsize messagesArrayLen = env->GetArrayLength(messages);
+
+  if (messagesArrayLen < messagesToRead) {
+    messagesToRead = messagesArrayLen;
+  }
+
   uint32_t handle = static_cast<uint32_t>(sessionHandle);
   uint32_t messagesRead = 0;
 
@@ -151,7 +162,8 @@
     return 0;
   }
 
-  if (!CheckStatus(env, status)) {
+  if (status != HAL_ERR_CANSessionMux_SessionOverrun &&
+      !CheckStatus(env, status)) {
     return 0;
   }
 
@@ -160,8 +172,15 @@
     JLocal<jobject> elem{
         env, static_cast<jstring>(env->GetObjectArrayElement(messages, i))};
     if (!elem) {
-      // TODO decide if should throw
-      continue;
+      // If element doesn't exist, construct it in place. If that fails, we are
+      // OOM, just return
+      elem = JLocal<jobject>{env, CreateCANStreamMessage(env)};
+      if (elem) {
+        std::printf("Allocated and set object\n");
+        env->SetObjectArrayElement(messages, i, elem);
+      } else {
+        return 0;
+      }
     }
     JLocal<jbyteArray> toSetArray{
         env, SetCANStreamObject(env, elem, msg->dataSize, msg->messageID,
@@ -174,6 +193,12 @@
                             reinterpret_cast<jbyte*>(msg->data));
   }
 
+  if (status == HAL_ERR_CANSessionMux_SessionOverrun) {
+    ThrowCANStreamOverflowException(env, messages,
+                                    static_cast<jint>(messagesRead));
+    return 0;
+  }
+
   return static_cast<jint>(messagesRead);
 }
 
diff --git a/hal/src/main/native/cpp/jni/HALUtil.cpp b/hal/src/main/native/cpp/jni/HALUtil.cpp
index 6316a8c..1915108 100644
--- a/hal/src/main/native/cpp/jni/HALUtil.cpp
+++ b/hal/src/main/native/cpp/jni/HALUtil.cpp
@@ -46,6 +46,7 @@
 static JException canMessageNotAllowedExCls;
 static JException canNotInitializedExCls;
 static JException uncleanStatusExCls;
+static JException nullPointerEx;
 static JClass powerDistributionVersionCls;
 static JClass pwmConfigDataResultCls;
 static JClass canStatusCls;
@@ -56,6 +57,7 @@
 static JClass halValueCls;
 static JClass baseStoreCls;
 static JClass revPHVersionCls;
+static JClass canStreamOverflowExCls;
 
 static const JClassInit classes[] = {
     {"edu/wpi/first/hal/PowerDistributionVersion",
@@ -68,7 +70,9 @@
     {"edu/wpi/first/hal/CANStreamMessage", &canStreamMessageCls},
     {"edu/wpi/first/hal/HALValue", &halValueCls},
     {"edu/wpi/first/hal/DMAJNISample$BaseStore", &baseStoreCls},
-    {"edu/wpi/first/hal/REVPHVersion", &revPHVersionCls}};
+    {"edu/wpi/first/hal/REVPHVersion", &revPHVersionCls},
+    {"edu/wpi/first/hal/can/CANStreamOverflowException",
+     &canStreamOverflowExCls}};
 
 static const JExceptionInit exceptions[] = {
     {"java/lang/IllegalArgumentException", &illegalArgExCls},
@@ -82,7 +86,8 @@
      &canMessageNotAllowedExCls},
     {"edu/wpi/first/hal/can/CANNotInitializedException",
      &canNotInitializedExCls},
-    {"edu/wpi/first/hal/util/UncleanStatusException", &uncleanStatusExCls}};
+    {"edu/wpi/first/hal/util/UncleanStatusException", &uncleanStatusExCls},
+    {"java/lang/NullPointerException", &nullPointerEx}};
 
 namespace hal {
 
@@ -209,6 +214,20 @@
   }
 }
 
+void ThrowNullPointerException(JNIEnv* env, std::string_view msg) {
+  nullPointerEx.Throw(env, msg);
+}
+
+void ThrowCANStreamOverflowException(JNIEnv* env, jobjectArray messages,
+                                     jint length) {
+  static jmethodID constructor =
+      env->GetMethodID(canStreamOverflowExCls, "<init>",
+                       "([Ledu/wpi/first/hal/CANStreamMessage;I)V");
+  jobject exception =
+      env->NewObject(canStreamOverflowExCls, constructor, messages, length);
+  env->Throw(static_cast<jthrowable>(exception));
+}
+
 void ThrowIllegalArgumentException(JNIEnv* env, std::string_view msg) {
   illegalArgExCls.Throw(env, msg);
 }
@@ -365,6 +384,12 @@
       static_cast<jint>(hardwareMajor), static_cast<jint>(uniqueId));
 }
 
+jobject CreateCANStreamMessage(JNIEnv* env) {
+  static jmethodID constructor =
+      env->GetMethodID(canStreamMessageCls, "<init>", "()V");
+  return env->NewObject(canStreamMessageCls, constructor);
+}
+
 JavaVM* GetJVM() {
   return jvm;
 }
diff --git a/hal/src/main/native/cpp/jni/HALUtil.h b/hal/src/main/native/cpp/jni/HALUtil.h
index 9c9487c..b64238b 100644
--- a/hal/src/main/native/cpp/jni/HALUtil.h
+++ b/hal/src/main/native/cpp/jni/HALUtil.h
@@ -51,6 +51,9 @@
   return status == 0;
 }
 
+void ThrowNullPointerException(JNIEnv* env, std::string_view msg);
+void ThrowCANStreamOverflowException(JNIEnv* env, jobjectArray messages,
+                                     jint length);
 void ThrowIllegalArgumentException(JNIEnv* env, std::string_view msg);
 void ThrowBoundaryException(JNIEnv* env, double value, double lower,
                             double upper);
@@ -93,6 +96,8 @@
                                        uint32_t hardwareMajor,
                                        uint32_t uniqueId);
 
+jobject CreateCANStreamMessage(JNIEnv* env);
+
 JavaVM* GetJVM();
 
 }  // namespace hal
diff --git a/hal/src/main/native/cpp/jni/LEDJNI.cpp b/hal/src/main/native/cpp/jni/LEDJNI.cpp
new file mode 100644
index 0000000..62aeaff
--- /dev/null
+++ b/hal/src/main/native/cpp/jni/LEDJNI.cpp
@@ -0,0 +1,51 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <fmt/core.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_LEDJNI.h"
+#include "hal/LEDs.h"
+
+static_assert(edu_wpi_first_hal_LEDJNI_RADIO_LED_STATE_OFF ==
+              HAL_RadioLEDState::HAL_RadioLED_kOff);
+static_assert(edu_wpi_first_hal_LEDJNI_RADIO_LED_STATE_GREEN ==
+              HAL_RadioLEDState::HAL_RadioLED_kGreen);
+static_assert(edu_wpi_first_hal_LEDJNI_RADIO_LED_STATE_RED ==
+              HAL_RadioLEDState::HAL_RadioLED_kRed);
+static_assert(edu_wpi_first_hal_LEDJNI_RADIO_LED_STATE_ORANGE ==
+              HAL_RadioLEDState::HAL_RadioLED_kOrange);
+
+using namespace hal;
+
+extern "C" {
+/*
+ * Class:     edu_wpi_first_hal_LEDJNI
+ * Method:    setRadioLEDState
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_LEDJNI_setRadioLEDState
+  (JNIEnv* env, jclass, jint state)
+{
+  int32_t status = 0;
+  HAL_SetRadioLEDState(static_cast<HAL_RadioLEDState>(state), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_LEDJNI
+ * Method:    getRadioLEDState
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_LEDJNI_getRadioLEDState
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  auto retVal = HAL_GetRadioLEDState(&status);
+  CheckStatus(env, status);
+  return retVal;
+}
+}  // extern "C"
diff --git a/hal/src/main/native/cpp/jni/simulation/RoboRioDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/RoboRioDataJNI.cpp
index 9555f59..c9a2aca 100644
--- a/hal/src/main/native/cpp/jni/simulation/RoboRioDataJNI.cpp
+++ b/hal/src/main/native/cpp/jni/simulation/RoboRioDataJNI.cpp
@@ -985,6 +985,57 @@
 
 /*
  * Class:     edu_wpi_first_hal_simulation_RoboRioDataJNI
+ * Method:    registerRadioLEDStateCallback
+ * Signature: (Ljava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_simulation_RoboRioDataJNI_registerRadioLEDStateCallback
+  (JNIEnv* env, jclass, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallbackNoIndex(
+      env, callback, initialNotify,
+      &HALSIM_RegisterRoboRioRadioLEDStateCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_simulation_RoboRioDataJNI
+ * Method:    cancelRadioLEDStateCallback
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_simulation_RoboRioDataJNI_cancelRadioLEDStateCallback
+  (JNIEnv* env, jclass, jint handle)
+{
+  return sim::FreeCallbackNoIndex(env, handle,
+                                  &HALSIM_CancelRoboRioRadioLEDStateCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_simulation_RoboRioDataJNI
+ * Method:    getRadioLEDState
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_simulation_RoboRioDataJNI_getRadioLEDState
+  (JNIEnv*, jclass)
+{
+  return HALSIM_GetRoboRioRadioLEDState();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_simulation_RoboRioDataJNI
+ * Method:    setRadioLEDState
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_simulation_RoboRioDataJNI_setRadioLEDState
+  (JNIEnv*, jclass, jint value)
+{
+  HALSIM_SetRoboRioRadioLEDState(static_cast<HAL_RadioLEDState>(value));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_simulation_RoboRioDataJNI
  * Method:    resetData
  * Signature: ()V
  */
diff --git a/hal/src/main/native/include/hal/.clang-tidy b/hal/src/main/native/include/hal/.clang-tidy
index 4f4edda..2631285 100644
--- a/hal/src/main/native/include/hal/.clang-tidy
+++ b/hal/src/main/native/include/hal/.clang-tidy
@@ -36,7 +36,6 @@
   bugprone-unhandled-self-assignment,
   bugprone-unused-raii,
   bugprone-virtual-near-miss,
-  cert-dcl58-cpp,
   cert-err52-cpp,
   cert-err60-cpp,
   cert-mem57-cpp,
@@ -54,7 +53,6 @@
   google-readability-avoid-underscore-in-googletest-name,
   google-readability-casting,
   google-runtime-operator,
-  llvm-twine-local,
   misc-definitions-in-headers,
   misc-misplaced-const,
   misc-new-delete-overloads,
diff --git a/hal/src/main/native/include/hal/Accelerometer.h b/hal/src/main/native/include/hal/Accelerometer.h
index 9131e83..ab48ca5 100644
--- a/hal/src/main/native/include/hal/Accelerometer.h
+++ b/hal/src/main/native/include/hal/Accelerometer.h
@@ -12,7 +12,6 @@
  * @{
  */
 
-// clang-format off
 /**
  * The acceptable accelerometer ranges.
  */
@@ -21,7 +20,6 @@
   HAL_AccelerometerRange_k4G = 1,
   HAL_AccelerometerRange_k8G = 2,
 };
-// clang-format on
 
 #ifdef __cplusplus
 extern "C" {
diff --git a/hal/src/main/native/include/hal/AnalogTrigger.h b/hal/src/main/native/include/hal/AnalogTrigger.h
index f4622e3..e678b68 100644
--- a/hal/src/main/native/include/hal/AnalogTrigger.h
+++ b/hal/src/main/native/include/hal/AnalogTrigger.h
@@ -14,7 +14,6 @@
  * @{
  */
 
-// clang-format off
 /**
  * The type of analog trigger to trigger on.
  */
@@ -24,7 +23,6 @@
   HAL_Trigger_kRisingPulse = 2,
   HAL_Trigger_kFallingPulse = 3
 };
-// clang-format on
 
 #ifdef __cplusplus
 extern "C" {
diff --git a/hal/src/main/native/include/hal/CANAPITypes.h b/hal/src/main/native/include/hal/CANAPITypes.h
index decaf86..247732c 100644
--- a/hal/src/main/native/include/hal/CANAPITypes.h
+++ b/hal/src/main/native/include/hal/CANAPITypes.h
@@ -14,25 +14,37 @@
  * @{
  */
 
-// clang-format off
 /**
  * The CAN device type.
  *
  * Teams should use HAL_CAN_Dev_kMiscellaneous
  */
 HAL_ENUM(HAL_CANDeviceType) {
+  /// Broadcast.
   HAL_CAN_Dev_kBroadcast = 0,
+  /// Robot controller.
   HAL_CAN_Dev_kRobotController = 1,
+  /// Motor controller.
   HAL_CAN_Dev_kMotorController = 2,
+  /// Relay controller.
   HAL_CAN_Dev_kRelayController = 3,
+  /// Gyro sensor.
   HAL_CAN_Dev_kGyroSensor = 4,
+  /// Accelerometer.
   HAL_CAN_Dev_kAccelerometer = 5,
+  /// Ultrasonic sensor.
   HAL_CAN_Dev_kUltrasonicSensor = 6,
+  /// Gear tooth sensor.
   HAL_CAN_Dev_kGearToothSensor = 7,
+  /// Power distribution.
   HAL_CAN_Dev_kPowerDistribution = 8,
+  /// Pneumatics.
   HAL_CAN_Dev_kPneumatics = 9,
+  /// Miscellaneous.
   HAL_CAN_Dev_kMiscellaneous = 10,
+  /// IO breakout.
   HAL_CAN_Dev_kIOBreakout = 11,
+  /// Firmware update.
   HAL_CAN_Dev_kFirmwareUpdate = 31
 };
 
@@ -42,23 +54,39 @@
  * Teams should use HAL_CAN_Man_kTeamUse.
  */
 HAL_ENUM(HAL_CANManufacturer) {
+  /// Broadcast.
   HAL_CAN_Man_kBroadcast = 0,
+  /// National Instruments.
   HAL_CAN_Man_kNI = 1,
+  /// Luminary Micro.
   HAL_CAN_Man_kLM = 2,
+  /// DEKA Research and Development Corp.
   HAL_CAN_Man_kDEKA = 3,
+  /// Cross the Road Electronics.
   HAL_CAN_Man_kCTRE = 4,
+  /// REV robotics.
   HAL_CAN_Man_kREV = 5,
+  /// Grapple.
   HAL_CAN_Man_kGrapple = 6,
+  /// MindSensors.
   HAL_CAN_Man_kMS = 7,
+  /// Team use.
   HAL_CAN_Man_kTeamUse = 8,
+  /// Kauai Labs.
   HAL_CAN_Man_kKauaiLabs = 9,
+  /// Copperforge.
   HAL_CAN_Man_kCopperforge = 10,
+  /// Playing With Fusion.
   HAL_CAN_Man_kPWF = 11,
+  /// Studica.
   HAL_CAN_Man_kStudica = 12,
+  /// TheThriftyBot.
   HAL_CAN_Man_kTheThriftyBot = 13,
+  /// Redux Robotics.
   HAL_CAN_Man_kReduxRobotics = 14,
+  /// AndyMark.
   HAL_CAN_Man_kAndyMark = 15,
+  /// Vivid-Hosting.
   HAL_CAN_Man_kVividHosting = 16
 };
-// clang-format on
 /** @} */
diff --git a/hal/src/main/native/include/hal/Counter.h b/hal/src/main/native/include/hal/Counter.h
index 0338cda..9c9d3af 100644
--- a/hal/src/main/native/include/hal/Counter.h
+++ b/hal/src/main/native/include/hal/Counter.h
@@ -15,7 +15,6 @@
  * @{
  */
 
-// clang-format off
 /**
  * The counter mode.
  */
@@ -25,7 +24,6 @@
   HAL_Counter_kPulseLength = 2,
   HAL_Counter_kExternalDirection = 3
 };
-// clang-format on
 
 #ifdef __cplusplus
 extern "C" {
diff --git a/hal/src/main/native/include/hal/DMA.h b/hal/src/main/native/include/hal/DMA.h
index b735b6d..2d570a4 100644
--- a/hal/src/main/native/include/hal/DMA.h
+++ b/hal/src/main/native/include/hal/DMA.h
@@ -13,7 +13,6 @@
  * @{
  */
 
-// clang-format off
 /**
  * The DMA Read Status.
  */
@@ -22,7 +21,6 @@
   HAL_DMA_TIMEOUT = 2,
   HAL_DMA_ERROR = 3,
 };
-// clang-format on
 
 /**
  * Buffer for containing all DMA data for a specific sample.
@@ -140,6 +138,8 @@
 /**
  * Adds timer data for an counter to be collected by DMA.
  *
+ * This can only be called if DMA is not started.
+ *
  * @param[in] handle the dma handle
  * @param[in] counterHandle the counter to add
  * @param[out] status Error status variable. 0 on success.
diff --git a/hal/src/main/native/include/hal/DriverStation.h b/hal/src/main/native/include/hal/DriverStation.h
index 5edacf5..e079074 100644
--- a/hal/src/main/native/include/hal/DriverStation.h
+++ b/hal/src/main/native/include/hal/DriverStation.h
@@ -6,6 +6,8 @@
 
 #include <stdint.h>
 
+#include <stddef.h>  //NOLINT
+
 #include <wpi/Synchronization.h>
 
 #include "hal/DriverStationTypes.h"
diff --git a/hal/src/main/native/include/hal/DriverStationTypes.h b/hal/src/main/native/include/hal/DriverStationTypes.h
index 5917c51..8282024 100644
--- a/hal/src/main/native/include/hal/DriverStationTypes.h
+++ b/hal/src/main/native/include/hal/DriverStationTypes.h
@@ -40,7 +40,6 @@
 };
 typedef struct HAL_ControlWord HAL_ControlWord;
 
-// clang-format off
 HAL_ENUM(HAL_AllianceStationID) {
   HAL_AllianceStationID_kUnknown = 0,
   HAL_AllianceStationID_kRed1,
@@ -57,7 +56,6 @@
   HAL_kMatchType_qualification,
   HAL_kMatchType_elimination,
 };
-// clang-format on
 
 /* The maximum number of axes that will be stored in a single HALJoystickAxes
  * struct. This is used for allocating buffers, not bounds checking, since
diff --git a/hal/src/main/native/include/hal/Encoder.h b/hal/src/main/native/include/hal/Encoder.h
index c6e16a6..451f1aa 100644
--- a/hal/src/main/native/include/hal/Encoder.h
+++ b/hal/src/main/native/include/hal/Encoder.h
@@ -15,7 +15,6 @@
  * @{
  */
 
-// clang-format off
 /**
  * The type of index pulse for the encoder.
  */
@@ -34,7 +33,6 @@
   HAL_Encoder_k2X,
   HAL_Encoder_k4X
 };
-// clang-format on
 
 #ifdef __cplusplus
 extern "C" {
diff --git a/hal/src/main/native/include/hal/HAL.h b/hal/src/main/native/include/hal/HAL.h
index 0d60237..84bee9f 100644
--- a/hal/src/main/native/include/hal/HAL.h
+++ b/hal/src/main/native/include/hal/HAL.h
@@ -25,6 +25,7 @@
 #include "hal/HALBase.h"
 #include "hal/I2C.h"
 #include "hal/Interrupts.h"
+#include "hal/LEDs.h"
 #include "hal/Main.h"
 #include "hal/Notifier.h"
 #include "hal/PWM.h"
diff --git a/hal/src/main/native/include/hal/HALBase.h b/hal/src/main/native/include/hal/HALBase.h
index fe8d1bf..3e9ddc6 100644
--- a/hal/src/main/native/include/hal/HALBase.h
+++ b/hal/src/main/native/include/hal/HALBase.h
@@ -22,9 +22,11 @@
  * @{
  */
 
-// clang-format off
-HAL_ENUM(HAL_RuntimeType) { HAL_Runtime_RoboRIO, HAL_Runtime_RoboRIO2, HAL_Runtime_Simulation };
-// clang-format on
+HAL_ENUM(HAL_RuntimeType) {
+  HAL_Runtime_RoboRIO,
+  HAL_Runtime_RoboRIO2,
+  HAL_Runtime_Simulation
+};
 
 #ifdef __cplusplus
 extern "C" {
@@ -108,6 +110,10 @@
 /**
  * Gets the state of the "USER" button on the roboRIO.
  *
+ * @warning the User Button is used to stop user programs from automatically
+ * loading if it is held for more then 5 seconds. Because of this, it's not
+ * recommended to be used by teams for any other purpose.
+ *
  * @param[out] status the error code, or 0 for success
  * @return true if the button is currently pressed down
  */
diff --git a/hal/src/main/native/include/hal/I2CTypes.h b/hal/src/main/native/include/hal/I2CTypes.h
index 6aac0fb..8c658ee 100644
--- a/hal/src/main/native/include/hal/I2CTypes.h
+++ b/hal/src/main/native/include/hal/I2CTypes.h
@@ -14,9 +14,11 @@
  * @{
  */
 
-// clang-format off
-HAL_ENUM(HAL_I2CPort) { HAL_I2C_kInvalid = -1, HAL_I2C_kOnboard, HAL_I2C_kMXP };
-// clang-format on
+HAL_ENUM(HAL_I2CPort) {
+  HAL_I2C_kInvalid = -1,
+  HAL_I2C_kOnboard,
+  HAL_I2C_kMXP
+};
 
 #ifdef __cplusplus
 namespace hal {
diff --git a/hal/src/main/native/include/hal/LEDs.h b/hal/src/main/native/include/hal/LEDs.h
new file mode 100644
index 0000000..d7ee716
--- /dev/null
+++ b/hal/src/main/native/include/hal/LEDs.h
@@ -0,0 +1,34 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#pragma once
+#include "hal/Types.h"
+
+HAL_ENUM(HAL_RadioLEDState) {
+  HAL_RadioLED_kOff = 0,
+  HAL_RadioLED_kGreen = 1,
+  HAL_RadioLED_kRed = 2,
+  HAL_RadioLED_kOrange = 3
+};
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+/**
+ * Set the state of the "Radio" LED.
+ * @param state The state to set the LED to.
+ * @param[out] status the error code, or 0 for success
+ */
+void HAL_SetRadioLEDState(HAL_RadioLEDState state, int32_t* status);
+
+/**
+ * Get the state of the "Radio" LED.
+ *
+ * @param[out] status the error code, or 0 for success
+ * @return The state of the LED.
+ */
+HAL_RadioLEDState HAL_GetRadioLEDState(int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
diff --git a/hal/src/main/native/include/hal/PowerDistribution.h b/hal/src/main/native/include/hal/PowerDistribution.h
index 47543bb..c2dc3cd 100644
--- a/hal/src/main/native/include/hal/PowerDistribution.h
+++ b/hal/src/main/native/include/hal/PowerDistribution.h
@@ -15,7 +15,6 @@
  * @{
  */
 
-// clang-format off
 /**
  * The types of power distribution devices.
  */
@@ -24,7 +23,6 @@
   HAL_PowerDistributionType_kCTRE = 1,
   HAL_PowerDistributionType_kRev = 2,
 };
-// clang-format on
 
 #define HAL_DEFAULT_POWER_DISTRIBUTION_MODULE -1
 
@@ -219,12 +217,21 @@
 HAL_Bool HAL_GetPowerDistributionSwitchableChannel(
     HAL_PowerDistributionHandle handle, int32_t* status);
 
+/**
+ * Power distribution version.
+ */
 struct HAL_PowerDistributionVersion {
+  /// Firmware major version number.
   uint32_t firmwareMajor;
+  /// Firmware minor version number.
   uint32_t firmwareMinor;
+  /// Firmware fix version number.
   uint32_t firmwareFix;
+  /// Hardware minor version number.
   uint32_t hardwareMinor;
+  /// Hardware major version number.
   uint32_t hardwareMajor;
+  /// Unique ID.
   uint32_t uniqueId;
 };
 
@@ -324,6 +331,24 @@
     HAL_PowerDistributionHandle handle,
     HAL_PowerDistributionStickyFaults* stickyFaults, int32_t* status);
 
+void HAL_StartPowerDistributionStream(HAL_PowerDistributionHandle handle,
+                                      int32_t* status);
+
+typedef struct HAL_PowerDistributionChannelData {
+  float current;
+  int32_t channel;
+  uint32_t timestamp;
+} HAL_PowerDistributionChannelData;
+
+HAL_PowerDistributionChannelData* HAL_GetPowerDistributionStreamData(
+    HAL_PowerDistributionHandle handle, int32_t* count, int32_t* status);
+
+void HAL_FreePowerDistributionStreamData(HAL_PowerDistributionChannelData* data,
+                                         int32_t count);
+
+void HAL_StopPowerDistributionStream(HAL_PowerDistributionHandle handle,
+                                     int32_t* status);
+
 #ifdef __cplusplus
 }  // extern "C"
 #endif
diff --git a/hal/src/main/native/include/hal/REVPH.h b/hal/src/main/native/include/hal/REVPH.h
index 4476675..754c0f2 100644
--- a/hal/src/main/native/include/hal/REVPH.h
+++ b/hal/src/main/native/include/hal/REVPH.h
@@ -17,11 +17,11 @@
 /**
  * The compressor configuration type
  */
-HAL_ENUM(HAL_REVPHCompressorConfigType){
-    HAL_REVPHCompressorConfigType_kDisabled = 0,
-    HAL_REVPHCompressorConfigType_kDigital = 1,
-    HAL_REVPHCompressorConfigType_kAnalog = 2,
-    HAL_REVPHCompressorConfigType_kHybrid = 3,
+HAL_ENUM(HAL_REVPHCompressorConfigType) {
+  HAL_REVPHCompressorConfigType_kDisabled = 0,
+  HAL_REVPHCompressorConfigType_kDigital = 1,
+  HAL_REVPHCompressorConfigType_kAnalog = 2,
+  HAL_REVPHCompressorConfigType_kHybrid = 3,
 };
 
 /**
diff --git a/hal/src/main/native/include/hal/SPITypes.h b/hal/src/main/native/include/hal/SPITypes.h
index 34b5d61..d521665 100644
--- a/hal/src/main/native/include/hal/SPITypes.h
+++ b/hal/src/main/native/include/hal/SPITypes.h
@@ -14,7 +14,6 @@
  * @{
  */
 
-// clang-format off
 HAL_ENUM(HAL_SPIPort) {
   HAL_SPI_kInvalid = -1,
   HAL_SPI_kOnboardCS0,
@@ -23,16 +22,13 @@
   HAL_SPI_kOnboardCS3,
   HAL_SPI_kMXP
 };
-// clang-format on
 
-// clang-format off
 HAL_ENUM(HAL_SPIMode) {
   HAL_SPI_kMode0 = 0,
   HAL_SPI_kMode1 = 1,
   HAL_SPI_kMode2 = 2,
   HAL_SPI_kMode3 = 3,
 };
-// clang-format on
 
 #ifdef __cplusplus
 namespace hal {
diff --git a/hal/src/main/native/include/hal/SerialPort.h b/hal/src/main/native/include/hal/SerialPort.h
index f4a357e..c6b80c7 100644
--- a/hal/src/main/native/include/hal/SerialPort.h
+++ b/hal/src/main/native/include/hal/SerialPort.h
@@ -14,14 +14,12 @@
  * @{
  */
 
-// clang-format off
 HAL_ENUM(HAL_SerialPort) {
   HAL_SerialPort_Onboard = 0,
   HAL_SerialPort_MXP = 1,
   HAL_SerialPort_USB1 = 2,
   HAL_SerialPort_USB2 = 3
 };
-// clang-format on
 
 #ifdef __cplusplus
 extern "C" {
diff --git a/hal/src/main/native/include/hal/SimDevice.h b/hal/src/main/native/include/hal/SimDevice.h
index 0e75cea..e5e3324 100644
--- a/hal/src/main/native/include/hal/SimDevice.h
+++ b/hal/src/main/native/include/hal/SimDevice.h
@@ -30,13 +30,11 @@
 /**
  * Direction of a simulated value (from the perspective of user code).
  */
-// clang-format off
 HAL_ENUM(HAL_SimValueDirection) {
-  HAL_SimValueInput = 0,  /**< input to user code from the simulator */
-  HAL_SimValueOutput,     /**< output from user code to the simulator */
-  HAL_SimValueBidir       /**< bidirectional between user code and simulator */
+  HAL_SimValueInput = 0, /**< input to user code from the simulator */
+  HAL_SimValueOutput,    /**< output from user code to the simulator */
+  HAL_SimValueBidir      /**< bidirectional between user code and simulator */
 };
-// clang-format on
 
 #ifdef __cplusplus
 extern "C" {
diff --git a/hal/src/main/native/include/hal/simulation/RoboRioData.h b/hal/src/main/native/include/hal/simulation/RoboRioData.h
index d191fcb..83d68ea 100644
--- a/hal/src/main/native/include/hal/simulation/RoboRioData.h
+++ b/hal/src/main/native/include/hal/simulation/RoboRioData.h
@@ -6,6 +6,7 @@
 
 #include <cstddef>
 
+#include "hal/LEDs.h"
 #include "hal/Types.h"
 #include "hal/simulation/NotifyListener.h"
 
@@ -145,9 +146,6 @@
 size_t HALSIM_GetRoboRioComments(char* buffer, size_t size);
 void HALSIM_SetRoboRioComments(const char* comments, size_t size);
 
-void HALSIM_RegisterRoboRioAllCallbacks(HAL_NotifyCallback callback,
-                                        void* param, HAL_Bool initialNotify);
-
 int32_t HALSIM_RegisterRoboRioCPUTempCallback(HAL_NotifyCallback callback,
                                               void* param,
                                               HAL_Bool initialNotify);
@@ -155,6 +153,15 @@
 double HALSIM_GetRoboRioCPUTemp(void);
 void HALSIM_SetRoboRioCPUTemp(double cpuTemp);
 
+int32_t HALSIM_RegisterRoboRioRadioLEDStateCallback(HAL_NotifyCallback callback,
+                                                    void* param,
+                                                    HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioRadioLEDStateCallback(int32_t uid);
+HAL_RadioLEDState HALSIM_GetRoboRioRadioLEDState(void);
+void HALSIM_SetRoboRioRadioLEDState(HAL_RadioLEDState state);
+
+void HALSIM_RegisterRoboRioAllCallbacks(HAL_NotifyCallback callback,
+                                        void* param, HAL_Bool initialNotify);
 #ifdef __cplusplus
 }  // extern "C"
 #endif
diff --git a/hal/src/main/native/sim/HAL.cpp b/hal/src/main/native/sim/HAL.cpp
index ce8b6dd..c7b632c 100644
--- a/hal/src/main/native/sim/HAL.cpp
+++ b/hal/src/main/native/sim/HAL.cpp
@@ -367,12 +367,12 @@
 #ifdef _WIN32
   TIMECAPS tc;
   if (timeGetDevCaps(&tc, sizeof(tc)) == TIMERR_NOERROR) {
-    UINT target = min(1, tc.wPeriodMin);
+    UINT target = (std::min)(static_cast<UINT>(1), tc.wPeriodMin);
     timeBeginPeriod(target);
     std::atexit([]() {
       TIMECAPS tc;
       if (timeGetDevCaps(&tc, sizeof(tc)) == TIMERR_NOERROR) {
-        UINT target = min(1, tc.wPeriodMin);
+        UINT target = (std::min)(static_cast<UINT>(1), tc.wPeriodMin);
         timeEndPeriod(target);
       }
     });
diff --git a/hal/src/main/native/sim/LEDs.cpp b/hal/src/main/native/sim/LEDs.cpp
new file mode 100644
index 0000000..e7d45aa
--- /dev/null
+++ b/hal/src/main/native/sim/LEDs.cpp
@@ -0,0 +1,21 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include "hal/LEDs.h"
+
+#include "hal/simulation/RoboRioData.h"
+
+namespace hal::init {
+void InitializeLEDs() {}
+}  // namespace hal::init
+
+extern "C" {
+
+void HAL_SetRadioLEDState(HAL_RadioLEDState state, int32_t* status) {
+  HALSIM_SetRoboRioRadioLEDState(state);
+}
+HAL_RadioLEDState HAL_GetRadioLEDState(int32_t* status) {
+  return HALSIM_GetRoboRioRadioLEDState();
+}
+}  // extern "C"
diff --git a/hal/src/main/native/sim/mockdata/RoboRioData.cpp b/hal/src/main/native/sim/mockdata/RoboRioData.cpp
index 9a9a1a1..8ccc019 100644
--- a/hal/src/main/native/sim/mockdata/RoboRioData.cpp
+++ b/hal/src/main/native/sim/mockdata/RoboRioData.cpp
@@ -136,6 +136,7 @@
 DEFINE_CAPI(double, BrownoutVoltage, brownoutVoltage)
 DEFINE_CAPI(double, CPUTemp, cpuTemp)
 DEFINE_CAPI(int32_t, TeamNumber, teamNumber)
+DEFINE_CAPI(HAL_RadioLEDState, RadioLEDState, radioLedState)
 
 int32_t HALSIM_RegisterRoboRioSerialNumberCallback(
     HAL_RoboRioStringCallback callback, void* param, HAL_Bool initialNotify) {
@@ -192,5 +193,6 @@
   REGISTER(userFaults3V3);
   REGISTER(brownoutVoltage);
   REGISTER(cpuTemp);
+  REGISTER(radioLedState);
 }
 }  // extern "C"
diff --git a/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h b/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h
index aef61be..413c38e 100644
--- a/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h
+++ b/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h
@@ -32,10 +32,15 @@
   HAL_SIMDATAVALUE_DEFINE_NAME(BrownoutVoltage)
   HAL_SIMDATAVALUE_DEFINE_NAME(CPUTemp)
   HAL_SIMDATAVALUE_DEFINE_NAME(TeamNumber)
+  HAL_SIMDATAVALUE_DEFINE_NAME(RadioLEDState)
 
   HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(SerialNumber)
   HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(Comments);
 
+  static inline HAL_Value MakeRadioLEDStateValue(HAL_RadioLEDState value) {
+    return HAL_MakeEnum(value);
+  }
+
  public:
   SimDataValue<HAL_Bool, HAL_MakeBoolean, GetFPGAButtonName> fpgaButton{false};
   SimDataValue<double, HAL_MakeDouble, GetVInVoltageName> vInVoltage{12.0};
@@ -61,6 +66,8 @@
       6.75};
   SimDataValue<double, HAL_MakeDouble, GetCPUTempName> cpuTemp{45.0};
   SimDataValue<int32_t, HAL_MakeInt, GetTeamNumberName> teamNumber{0};
+  SimDataValue<HAL_RadioLEDState, MakeRadioLEDStateValue, GetRadioLEDStateName>
+      radioLedState{HAL_RadioLED_kOff};
 
   int32_t RegisterSerialNumberCallback(HAL_RoboRioStringCallback callback,
                                        void* param, HAL_Bool initialNotify);