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/wpilibc/src/main/native/cpp/ADIS16448_IMU.cpp b/wpilibc/src/main/native/cpp/ADIS16448_IMU.cpp
index 14fd37f..4ce4197 100644
--- a/wpilibc/src/main/native/cpp/ADIS16448_IMU.cpp
+++ b/wpilibc/src/main/native/cpp/ADIS16448_IMU.cpp
@@ -679,8 +679,13 @@
   return compAngle;
 }
 
-int ADIS16448_IMU::ConfigDecRate(uint16_t DecimationSetting) {
-  uint16_t writeValue = DecimationSetting;
+int ADIS16448_IMU::ConfigDecRate(uint16_t decimationRate) {
+  // Switches the active SPI port to standard SPI mode, writes a new value to
+  // the DECIMATE register in the IMU, and re-enables auto SPI.
+  //
+  // This function enters standard SPI mode, writes a new DECIMATE setting to
+  // the IMU, adjusts the sample scale factor, and re-enters auto SPI mode.
+  uint16_t writeValue = decimationRate;
   uint16_t readbackValue;
   if (!SwitchToStandardSPI()) {
     REPORT_ERROR("Failed to configure/reconfigure standard SPI.");
@@ -688,14 +693,14 @@
   }
 
   /* Check max */
-  if (DecimationSetting > 9) {
+  if (decimationRate > 9) {
     REPORT_ERROR(
         "Attempted to write an invalid decimation value. Capping at 9");
-    DecimationSetting = 9;
+    decimationRate = 9;
   }
 
   /* Shift decimation setting to correct position and select internal sync */
-  writeValue = (DecimationSetting << 8) | 0x1;
+  writeValue = (decimationRate << 8) | 0x1;
 
   /* Apply to IMU */
   WriteRegister(SMPL_PRD, writeValue);
diff --git a/wpilibc/src/main/native/cpp/ADIS16470_IMU.cpp b/wpilibc/src/main/native/cpp/ADIS16470_IMU.cpp
index 05dac78..1c5c7a1 100644
--- a/wpilibc/src/main/native/cpp/ADIS16470_IMU.cpp
+++ b/wpilibc/src/main/native/cpp/ADIS16470_IMU.cpp
@@ -63,14 +63,35 @@
  * Constructor.
  */
 ADIS16470_IMU::ADIS16470_IMU()
-    : ADIS16470_IMU(kZ, SPI::Port::kOnboardCS0, CalibrationTime::_4s) {}
+    : ADIS16470_IMU(kZ, kY, kX, SPI::Port::kOnboardCS0, CalibrationTime::_4s) {}
 
-ADIS16470_IMU::ADIS16470_IMU(IMUAxis yaw_axis, SPI::Port port,
+ADIS16470_IMU::ADIS16470_IMU(IMUAxis yaw_axis, IMUAxis pitch_axis,
+                             IMUAxis roll_axis)
+    : ADIS16470_IMU(yaw_axis, pitch_axis, roll_axis, SPI::Port::kOnboardCS0,
+                    CalibrationTime::_4s) {}
+
+ADIS16470_IMU::ADIS16470_IMU(IMUAxis yaw_axis, IMUAxis pitch_axis,
+                             IMUAxis roll_axis, SPI::Port port,
                              CalibrationTime cal_time)
     : m_yaw_axis(yaw_axis),
+      m_pitch_axis(pitch_axis),
+      m_roll_axis(roll_axis),
       m_spi_port(port),
       m_calibration_time(static_cast<uint16_t>(cal_time)),
       m_simDevice("Gyro:ADIS16470", port) {
+  if (yaw_axis == kYaw || yaw_axis == kPitch || yaw_axis == kRoll ||
+      pitch_axis == kYaw || pitch_axis == kPitch || pitch_axis == kRoll ||
+      roll_axis == kYaw || roll_axis == kPitch || roll_axis == kRoll) {
+    REPORT_ERROR(
+        "ADIS16470 constructor only allows IMUAxis.kX, IMUAxis.kY or "
+        "IMUAxis.kZ as arguments.");
+    REPORT_ERROR(
+        "Constructing ADIS with default axes. (IMUAxis.kZ is defined as Yaw)");
+    yaw_axis = kZ;
+    pitch_axis = kY;
+    roll_axis = kX;
+  }
+
   if (m_simDevice) {
     m_connected =
         m_simDevice.CreateBoolean("connected", hal::SimDevice::kInput, true);
@@ -266,17 +287,8 @@
     m_auto_configured = true;
   }
   // Do we need to change auto SPI settings?
-  switch (m_yaw_axis) {
-    case kX:
-      m_spi->SetAutoTransmitData(m_autospi_x_packet, 2);
-      break;
-    case kY:
-      m_spi->SetAutoTransmitData(m_autospi_y_packet, 2);
-      break;
-    default:
-      m_spi->SetAutoTransmitData(m_autospi_z_packet, 2);
-      break;
-  }
+  m_spi->SetAutoTransmitData(m_autospi_allangle_packet, 2);
+
   // Configure auto stall time
   m_spi->ConfigureAutoStall(HAL_SPI_kOnboardCS0, 5, 1000, 1);
   // Kick off DMA SPI (Note: Device configuration impossible after SPI DMA is
@@ -336,31 +348,22 @@
   return 0;
 }
 
-/**
- * @brief Switches the active SPI port to standard SPI mode, writes a new value
- *to the DECIMATE register in the IMU, and re-enables auto SPI.
- *
- * @param reg Decimation value to be set.
- *
- * @return An int indicating the success or failure of writing the new DECIMATE
- *setting and returning to auto SPI mode. 0 = Success, 1 = No Change, 2 =
- *Failure
- *
- * This function enters standard SPI mode, writes a new DECIMATE setting to the
- *IMU, adjusts the sample scale factor, and re-enters auto SPI mode.
- **/
-int ADIS16470_IMU::ConfigDecRate(uint16_t reg) {
-  uint16_t m_reg = reg;
+int ADIS16470_IMU::ConfigDecRate(uint16_t decimationRate) {
+  // Switches the active SPI port to standard SPI mode, writes a new value to
+  // the DECIMATE register in the IMU, and re-enables auto SPI.
+  //
+  // This function enters standard SPI mode, writes a new DECIMATE setting to
+  // the IMU, adjusts the sample scale factor, and re-enters auto SPI mode.
   if (!SwitchToStandardSPI()) {
     REPORT_ERROR("Failed to configure/reconfigure standard SPI.");
     return 2;
   }
-  if (m_reg > 1999) {
+  if (decimationRate > 1999) {
     REPORT_ERROR("Attempted to write an invalid decimation value.");
-    m_reg = 1999;
+    decimationRate = 1999;
   }
-  m_scaled_sample_rate = (((m_reg + 1.0) / 2000.0) * 1000000.0);
-  WriteRegister(DEC_RATE, m_reg);
+  m_scaled_sample_rate = (((decimationRate + 1.0) / 2000.0) * 1000000.0);
+  WriteRegister(DEC_RATE, decimationRate);
   if (!SwitchToAutoSPI()) {
     REPORT_ERROR("Failed to configure/reconfigure auto SPI.");
     return 2;
@@ -445,7 +448,9 @@
  **/
 void ADIS16470_IMU::Reset() {
   std::scoped_lock sync(m_mutex);
-  m_integ_angle = 0.0;
+  m_integ_angle_x = 0.0;
+  m_integ_angle_y = 0.0;
+  m_integ_angle_z = 0.0;
 }
 
 void ADIS16470_IMU::Close() {
@@ -502,7 +507,7 @@
  **/
 void ADIS16470_IMU::Acquire() {
   // Set data packet length
-  const int dataset_len = 19;  // 18 data points + timestamp
+  const int dataset_len = 27;  // 26 data points + timestamp
 
   /* Fixed buffer size */
   const int BUFFER_SIZE = 4000;
@@ -513,7 +518,9 @@
   int data_remainder = 0;
   int data_to_read = 0;
   uint32_t previous_timestamp = 0;
-  double delta_angle = 0.0;
+  double delta_angle_x = 0.0;
+  double delta_angle_y = 0.0;
+  double delta_angle_z = 0.0;
   double gyro_rate_x = 0.0;
   double gyro_rate_y = 0.0;
   double gyro_rate_z = 0.0;
@@ -562,14 +569,22 @@
         m_dt = (buffer[i] - previous_timestamp) / 1000000.0;
         /* Get delta angle value for selected yaw axis and scale by the elapsed
          * time (based on timestamp) */
-        delta_angle = (ToInt(&buffer[i + 3]) * delta_angle_sf) /
-                      (m_scaled_sample_rate / (buffer[i] - previous_timestamp));
-        gyro_rate_x = (BuffToShort(&buffer[i + 7]) / 10.0);
-        gyro_rate_y = (BuffToShort(&buffer[i + 9]) / 10.0);
-        gyro_rate_z = (BuffToShort(&buffer[i + 11]) / 10.0);
-        accel_x = (BuffToShort(&buffer[i + 13]) / 800.0);
-        accel_y = (BuffToShort(&buffer[i + 15]) / 800.0);
-        accel_z = (BuffToShort(&buffer[i + 17]) / 800.0);
+        delta_angle_x =
+            (ToInt(&buffer[i + 3]) * delta_angle_sf) /
+            (m_scaled_sample_rate / (buffer[i] - previous_timestamp));
+        delta_angle_y =
+            (ToInt(&buffer[i + 7]) * delta_angle_sf) /
+            (m_scaled_sample_rate / (buffer[i] - previous_timestamp));
+        delta_angle_z =
+            (ToInt(&buffer[i + 11]) * delta_angle_sf) /
+            (m_scaled_sample_rate / (buffer[i] - previous_timestamp));
+
+        gyro_rate_x = (BuffToShort(&buffer[i + 15]) / 10.0);
+        gyro_rate_y = (BuffToShort(&buffer[i + 17]) / 10.0);
+        gyro_rate_z = (BuffToShort(&buffer[i + 19]) / 10.0);
+        accel_x = (BuffToShort(&buffer[i + 21]) / 800.0);
+        accel_y = (BuffToShort(&buffer[i + 23]) / 800.0);
+        accel_z = (BuffToShort(&buffer[i + 25]) / 800.0);
 
         // Convert scaled sensor data to SI units
         gyro_rate_x_si = gyro_rate_x * deg_to_rad;
@@ -611,9 +626,13 @@
           if (m_first_run) {
             /* Don't accumulate first run. previous_timestamp will be "very" old
              * and the integration will end up way off */
-            m_integ_angle = 0.0;
+            m_integ_angle_x = 0.0;
+            m_integ_angle_y = 0.0;
+            m_integ_angle_z = 0.0;
           } else {
-            m_integ_angle += delta_angle;
+            m_integ_angle_x += delta_angle_x;
+            m_integ_angle_y += delta_angle_y;
+            m_integ_angle_z += delta_angle_z;
           }
           m_gyro_rate_x = gyro_rate_x;
           m_gyro_rate_y = gyro_rate_y;
@@ -634,7 +653,9 @@
       data_remainder = 0;
       data_to_read = 0;
       previous_timestamp = 0.0;
-      delta_angle = 0.0;
+      delta_angle_x = 0.0;
+      delta_angle_y = 0.0;
+      delta_angle_z = 0.0;
       gyro_rate_x = 0.0;
       gyro_rate_y = 0.0;
       gyro_rate_z = 0.0;
@@ -696,50 +717,143 @@
   return compAngle;
 }
 
-units::degree_t ADIS16470_IMU::GetAngle() const {
-  switch (m_yaw_axis) {
+void ADIS16470_IMU::SetGyroAngle(IMUAxis axis, units::degree_t angle) {
+  switch (axis) {
+    case kYaw:
+      axis = m_yaw_axis;
+      break;
+    case kPitch:
+      axis = m_pitch_axis;
+      break;
+    case kRoll:
+      axis = m_roll_axis;
+      break;
+    default:
+      break;
+  }
+
+  switch (axis) {
+    case kX:
+      SetGyroAngleX(angle);
+      break;
+    case kY:
+      SetGyroAngleY(angle);
+      break;
+    case kZ:
+      SetGyroAngleZ(angle);
+      break;
+    default:
+      break;
+  }
+}
+
+void ADIS16470_IMU::SetGyroAngleX(units::degree_t angle) {
+  std::scoped_lock sync(m_mutex);
+  m_integ_angle_x = angle.value();
+}
+
+void ADIS16470_IMU::SetGyroAngleY(units::degree_t angle) {
+  std::scoped_lock sync(m_mutex);
+  m_integ_angle_y = angle.value();
+}
+
+void ADIS16470_IMU::SetGyroAngleZ(units::degree_t angle) {
+  std::scoped_lock sync(m_mutex);
+  m_integ_angle_z = angle.value();
+}
+
+units::degree_t ADIS16470_IMU::GetAngle(IMUAxis axis) const {
+  switch (axis) {
+    case kYaw:
+      axis = m_yaw_axis;
+      break;
+    case kPitch:
+      axis = m_pitch_axis;
+      break;
+    case kRoll:
+      axis = m_roll_axis;
+      break;
+    default:
+      break;
+  }
+
+  switch (axis) {
     case kX:
       if (m_simGyroAngleX) {
         return units::degree_t{m_simGyroAngleX.Get()};
       }
-      break;
+      {
+        std::scoped_lock sync(m_mutex);
+        return units::degree_t{m_integ_angle_x};
+      }
     case kY:
       if (m_simGyroAngleY) {
         return units::degree_t{m_simGyroAngleY.Get()};
       }
-      break;
+      {
+        std::scoped_lock sync(m_mutex);
+        return units::degree_t{m_integ_angle_y};
+      }
     case kZ:
       if (m_simGyroAngleZ) {
         return units::degree_t{m_simGyroAngleZ.Get()};
       }
+      {
+        std::scoped_lock sync(m_mutex);
+        return units::degree_t{m_integ_angle_z};
+      }
+    default:
       break;
   }
-  std::scoped_lock sync(m_mutex);
-  return units::degree_t{m_integ_angle};
+
+  return units::degree_t{0.0};
 }
 
-units::degrees_per_second_t ADIS16470_IMU::GetRate() const {
-  if (m_yaw_axis == kX) {
-    if (m_simGyroRateX) {
-      return units::degrees_per_second_t{m_simGyroRateX.Get()};
-    }
-    std::scoped_lock sync(m_mutex);
-    return units::degrees_per_second_t{m_gyro_rate_x};
-  } else if (m_yaw_axis == kY) {
-    if (m_simGyroRateY) {
-      return units::degrees_per_second_t{m_simGyroRateY.Get()};
-    }
-    std::scoped_lock sync(m_mutex);
-    return units::degrees_per_second_t{m_gyro_rate_y};
-  } else if (m_yaw_axis == kZ) {
-    if (m_simGyroRateZ) {
-      return units::degrees_per_second_t{m_simGyroRateZ.Get()};
-    }
-    std::scoped_lock sync(m_mutex);
-    return units::degrees_per_second_t{m_gyro_rate_z};
-  } else {
-    return 0_deg_per_s;
+units::degrees_per_second_t ADIS16470_IMU::GetRate(IMUAxis axis) const {
+  switch (axis) {
+    case kYaw:
+      axis = m_yaw_axis;
+      break;
+    case kPitch:
+      axis = m_pitch_axis;
+      break;
+    case kRoll:
+      axis = m_roll_axis;
+      break;
+    default:
+      break;
   }
+
+  switch (axis) {
+    case kX:
+      if (m_simGyroRateX) {
+        return units::degrees_per_second_t{m_simGyroRateX.Get()};
+      }
+      {
+        std::scoped_lock sync(m_mutex);
+        return units::degrees_per_second_t{m_gyro_rate_x};
+      }
+    case kY:
+      if (m_simGyroRateY) {
+        return units::degrees_per_second_t{m_simGyroRateY.Get()};
+      }
+      {
+        std::scoped_lock sync(m_mutex);
+        return units::degrees_per_second_t{m_gyro_rate_y};
+      }
+    case kZ:
+      if (m_simGyroRateZ) {
+        return units::degrees_per_second_t{m_simGyroRateZ.Get()};
+      }
+      {
+        std::scoped_lock sync(m_mutex);
+        return units::degrees_per_second_t{m_gyro_rate_z};
+      }
+    default:
+      break;
+  }
+
+  return 0_deg_per_s;
 }
 
 units::meters_per_second_squared_t ADIS16470_IMU::GetAccelX() const {
@@ -790,20 +904,12 @@
   return m_yaw_axis;
 }
 
-int ADIS16470_IMU::SetYawAxis(IMUAxis yaw_axis) {
-  if (m_yaw_axis == yaw_axis) {
-    return 1;
-  }
-  if (!SwitchToStandardSPI()) {
-    REPORT_ERROR("Failed to configure/reconfigure standard SPI.");
-    return 2;
-  }
-  m_yaw_axis = yaw_axis;
-  if (!SwitchToAutoSPI()) {
-    REPORT_ERROR("Failed to configure/reconfigure auto SPI.");
-    return 2;
-  }
-  return 0;
+ADIS16470_IMU::IMUAxis ADIS16470_IMU::GetPitchAxis() const {
+  return m_pitch_axis;
+}
+
+ADIS16470_IMU::IMUAxis ADIS16470_IMU::GetRollAxis() const {
+  return m_roll_axis;
 }
 
 int ADIS16470_IMU::GetPort() const {
@@ -819,5 +925,5 @@
 void ADIS16470_IMU::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("ADIS16470 IMU");
   builder.AddDoubleProperty(
-      "Yaw Angle", [=, this] { return GetAngle().value(); }, nullptr);
+      "Yaw Angle", [=, this] { return GetAngle(kYaw).value(); }, nullptr);
 }
diff --git a/wpilibc/src/main/native/cpp/DMA.cpp b/wpilibc/src/main/native/cpp/DMA.cpp
index ce6c532..da45aa3 100644
--- a/wpilibc/src/main/native/cpp/DMA.cpp
+++ b/wpilibc/src/main/native/cpp/DMA.cpp
@@ -40,9 +40,9 @@
   FRC_CheckErrorStatus(status, "SetPause");
 }
 
-void DMA::SetTimedTrigger(units::second_t seconds) {
+void DMA::SetTimedTrigger(units::second_t period) {
   int32_t status = 0;
-  HAL_SetDMATimedTrigger(dmaHandle, seconds.value(), &status);
+  HAL_SetDMATimedTrigger(dmaHandle, period.value(), &status);
   FRC_CheckErrorStatus(status, "SetTimedTrigger");
 }
 
diff --git a/wpilibc/src/main/native/cpp/DataLogManager.cpp b/wpilibc/src/main/native/cpp/DataLogManager.cpp
index afe9330..09ac077 100644
--- a/wpilibc/src/main/native/cpp/DataLogManager.cpp
+++ b/wpilibc/src/main/native/cpp/DataLogManager.cpp
@@ -64,20 +64,26 @@
   }
 #ifdef __FRC_ROBORIO__
   // prefer a mounted USB drive if one is accessible
-  constexpr std::string_view usbDir{"/u"};
   std::error_code ec;
-  auto s = fs::status(usbDir, ec);
+  auto s = fs::status("/u", ec);
   if (!ec && fs::is_directory(s) &&
       (s.permissions() & fs::perms::others_write) != fs::perms::none) {
-    return std::string{usbDir};
+    fs::create_directory("/u/logs", ec);
+    return "/u/logs";
   }
   if (RobotBase::GetRuntimeType() == kRoboRIO) {
     FRC_ReportError(warn::Warning,
                     "DataLogManager: Logging to RoboRIO 1 internal storage is "
                     "not recommended! Plug in a FAT32 formatted flash drive!");
   }
+  fs::create_directory("/home/lvuser/logs", ec);
+  return "/home/lvuser/logs";
+#else
+  std::string logDir = filesystem::GetOperatingDirectory() + "/logs";
+  std::error_code ec;
+  fs::create_directory(logDir, ec);
+  return logDir;
 #endif
-  return filesystem::GetOperatingDirectory();
 }
 
 static std::string MakeLogFilename(std::string_view filenameOverride) {
@@ -328,7 +334,7 @@
 void DataLogManager::Stop() {
   auto& inst = GetInstance();
   inst.owner.GetThread()->m_log.Stop();
-  inst.owner.Stop();
+  inst.owner.Join();
 }
 
 void DataLogManager::Log(std::string_view message) {
diff --git a/wpilibc/src/main/native/cpp/I2C.cpp b/wpilibc/src/main/native/cpp/I2C.cpp
index da26c0c..232a47f 100644
--- a/wpilibc/src/main/native/cpp/I2C.cpp
+++ b/wpilibc/src/main/native/cpp/I2C.cpp
@@ -4,6 +4,7 @@
 
 #include "frc/I2C.h"
 
+#include <algorithm>
 #include <utility>
 
 #include <hal/FRCUsageReporting.h>
@@ -96,7 +97,7 @@
   uint8_t deviceData[4];
   for (int i = 0, curRegisterAddress = registerAddress; i < count;
        i += 4, curRegisterAddress += 4) {
-    int toRead = count - i < 4 ? count - i : 4;
+    int toRead = std::min(count - i, 4);
     // Read the chunk of data.  Return false if the sensor does not respond.
     if (Read(curRegisterAddress, toRead, deviceData)) {
       return false;
diff --git a/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp b/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp
index ee941b6..3669bce 100644
--- a/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp
+++ b/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp
@@ -8,6 +8,7 @@
 
 #include <fmt/format.h>
 #include <hal/DriverStation.h>
+#include <hal/FRCUsageReporting.h>
 #include <networktables/NetworkTableInstance.h>
 
 #include "frc/DSControlWord.h"
@@ -97,10 +98,16 @@
 }
 
 void IterativeRobotBase::EnableLiveWindowInTest(bool testLW) {
+  static bool hasReported;
   if (IsTestEnabled()) {
     throw FRC_MakeError(err::IncompatibleMode,
                         "Can't configure test mode while in test mode!");
   }
+  if (!hasReported && testLW) {
+    HAL_Report(HALUsageReporting::kResourceType_SmartDashboard,
+               HALUsageReporting::kSmartDashboard_LiveWindow);
+    hasReported = true;
+  }
   m_lwEnabledInTest = testLW;
 }
 
diff --git a/wpilibc/src/main/native/cpp/PS4Controller.cpp b/wpilibc/src/main/native/cpp/PS4Controller.cpp
index 5ac3420..e59e18c 100644
--- a/wpilibc/src/main/native/cpp/PS4Controller.cpp
+++ b/wpilibc/src/main/native/cpp/PS4Controller.cpp
@@ -11,8 +11,7 @@
 using namespace frc;
 
 PS4Controller::PS4Controller(int port) : GenericHID(port) {
-  // re-enable when PS4Controller is added to Usage Reporting
-  // HAL_Report(HALUsageReporting::kResourceType_PS4Controller, port + 1);
+  HAL_Report(HALUsageReporting::kResourceType_PS4Controller, port + 1);
 }
 
 double PS4Controller::GetLeftX() const {
diff --git a/wpilibc/src/main/native/cpp/PneumaticHub.cpp b/wpilibc/src/main/native/cpp/PneumaticHub.cpp
index bcbbd55..9101473 100644
--- a/wpilibc/src/main/native/cpp/PneumaticHub.cpp
+++ b/wpilibc/src/main/native/cpp/PneumaticHub.cpp
@@ -23,15 +23,15 @@
 /** Converts volts to PSI per the REV Analog Pressure Sensor datasheet. */
 units::pounds_per_square_inch_t VoltsToPSI(units::volt_t sensorVoltage,
                                            units::volt_t supplyVoltage) {
-  auto pressure = 250 * (sensorVoltage.value() / supplyVoltage.value()) - 25;
-  return units::pounds_per_square_inch_t{pressure};
+  return units::pounds_per_square_inch_t{
+      250 * (sensorVoltage.value() / supplyVoltage.value()) - 25};
 }
 
 /** Converts PSI to volts per the REV Analog Pressure Sensor datasheet. */
 units::volt_t PSIToVolts(units::pounds_per_square_inch_t pressure,
                          units::volt_t supplyVoltage) {
-  auto voltage = supplyVoltage.value() * (0.004 * pressure.value() + 0.1);
-  return units::volt_t{voltage};
+  return units::volt_t{supplyVoltage.value() *
+                       (0.004 * pressure.value() + 0.1)};
 }
 
 wpi::mutex PneumaticHub::m_handleLock;
@@ -339,6 +339,46 @@
   return stickyFaults;
 }
 
+bool PneumaticHub::Faults::GetChannelFault(int channel) const {
+  switch (channel) {
+    case 0:
+      return Channel0Fault != 0;
+    case 1:
+      return Channel1Fault != 0;
+    case 2:
+      return Channel2Fault != 0;
+    case 3:
+      return Channel3Fault != 0;
+    case 4:
+      return Channel4Fault != 0;
+    case 5:
+      return Channel5Fault != 0;
+    case 6:
+      return Channel6Fault != 0;
+    case 7:
+      return Channel7Fault != 0;
+    case 8:
+      return Channel8Fault != 0;
+    case 9:
+      return Channel9Fault != 0;
+    case 10:
+      return Channel10Fault != 0;
+    case 11:
+      return Channel11Fault != 0;
+    case 12:
+      return Channel12Fault != 0;
+    case 13:
+      return Channel13Fault != 0;
+    case 14:
+      return Channel14Fault != 0;
+    case 15:
+      return Channel15Fault != 0;
+    default:
+      throw FRC_MakeError(err::ChannelIndexOutOfRange,
+                          "Pneumatics fault channel out of bounds!");
+  }
+}
+
 void PneumaticHub::ClearStickyFaults() {
   int32_t status = 0;
   HAL_ClearREVPHStickyFaults(m_handle, &status);
diff --git a/wpilibc/src/main/native/cpp/PowerDistribution.cpp b/wpilibc/src/main/native/cpp/PowerDistribution.cpp
index ba4cb38..d645178 100644
--- a/wpilibc/src/main/native/cpp/PowerDistribution.cpp
+++ b/wpilibc/src/main/native/cpp/PowerDistribution.cpp
@@ -172,6 +172,118 @@
   return faults;
 }
 
+bool PowerDistribution::Faults::GetBreakerFault(int channel) const {
+  switch (channel) {
+    case 0:
+      return Channel0BreakerFault != 0;
+    case 1:
+      return Channel1BreakerFault != 0;
+    case 2:
+      return Channel2BreakerFault != 0;
+    case 3:
+      return Channel3BreakerFault != 0;
+    case 4:
+      return Channel4BreakerFault != 0;
+    case 5:
+      return Channel5BreakerFault != 0;
+    case 6:
+      return Channel6BreakerFault != 0;
+    case 7:
+      return Channel7BreakerFault != 0;
+    case 8:
+      return Channel8BreakerFault != 0;
+    case 9:
+      return Channel9BreakerFault != 0;
+    case 10:
+      return Channel10BreakerFault != 0;
+    case 11:
+      return Channel11BreakerFault != 0;
+    case 12:
+      return Channel12BreakerFault != 0;
+    case 13:
+      return Channel13BreakerFault != 0;
+    case 14:
+      return Channel14BreakerFault != 0;
+    case 15:
+      return Channel15BreakerFault != 0;
+    case 16:
+      return Channel16BreakerFault != 0;
+    case 17:
+      return Channel17BreakerFault != 0;
+    case 18:
+      return Channel18BreakerFault != 0;
+    case 19:
+      return Channel19BreakerFault != 0;
+    case 20:
+      return Channel20BreakerFault != 0;
+    case 21:
+      return Channel21BreakerFault != 0;
+    case 22:
+      return Channel22BreakerFault != 0;
+    case 23:
+      return Channel23BreakerFault != 0;
+    default:
+      throw FRC_MakeError(err::ChannelIndexOutOfRange,
+                          "Power distribution fault channel out of bounds!");
+  }
+}
+
+bool PowerDistribution::StickyFaults::GetBreakerFault(int channel) const {
+  switch (channel) {
+    case 0:
+      return Channel0BreakerFault != 0;
+    case 1:
+      return Channel1BreakerFault != 0;
+    case 2:
+      return Channel2BreakerFault != 0;
+    case 3:
+      return Channel3BreakerFault != 0;
+    case 4:
+      return Channel4BreakerFault != 0;
+    case 5:
+      return Channel5BreakerFault != 0;
+    case 6:
+      return Channel6BreakerFault != 0;
+    case 7:
+      return Channel7BreakerFault != 0;
+    case 8:
+      return Channel8BreakerFault != 0;
+    case 9:
+      return Channel9BreakerFault != 0;
+    case 10:
+      return Channel10BreakerFault != 0;
+    case 11:
+      return Channel11BreakerFault != 0;
+    case 12:
+      return Channel12BreakerFault != 0;
+    case 13:
+      return Channel13BreakerFault != 0;
+    case 14:
+      return Channel14BreakerFault != 0;
+    case 15:
+      return Channel15BreakerFault != 0;
+    case 16:
+      return Channel16BreakerFault != 0;
+    case 17:
+      return Channel17BreakerFault != 0;
+    case 18:
+      return Channel18BreakerFault != 0;
+    case 19:
+      return Channel19BreakerFault != 0;
+    case 20:
+      return Channel20BreakerFault != 0;
+    case 21:
+      return Channel21BreakerFault != 0;
+    case 22:
+      return Channel22BreakerFault != 0;
+    case 23:
+      return Channel23BreakerFault != 0;
+    default:
+      throw FRC_MakeError(err::ChannelIndexOutOfRange,
+                          "Power distribution fault channel out of bounds!");
+  }
+}
+
 PowerDistribution::StickyFaults PowerDistribution::GetStickyFaults() const {
   int32_t status = 0;
   HAL_PowerDistributionStickyFaults halStickyFaults;
diff --git a/wpilibc/src/main/native/cpp/RobotController.cpp b/wpilibc/src/main/native/cpp/RobotController.cpp
index 8b2b496..2414ed7 100644
--- a/wpilibc/src/main/native/cpp/RobotController.cpp
+++ b/wpilibc/src/main/native/cpp/RobotController.cpp
@@ -8,6 +8,7 @@
 
 #include <hal/CAN.h>
 #include <hal/HALBase.h>
+#include <hal/LEDs.h>
 #include <hal/Power.h>
 
 #include "frc/Errors.h"
@@ -230,6 +231,30 @@
   return units::celsius_t{retVal};
 }
 
+static_assert(RadioLEDState::kOff ==
+              static_cast<RadioLEDState>(HAL_RadioLEDState::HAL_RadioLED_kOff));
+static_assert(
+    RadioLEDState::kGreen ==
+    static_cast<RadioLEDState>(HAL_RadioLEDState::HAL_RadioLED_kGreen));
+static_assert(RadioLEDState::kRed ==
+              static_cast<RadioLEDState>(HAL_RadioLEDState::HAL_RadioLED_kRed));
+static_assert(
+    RadioLEDState::kOrange ==
+    static_cast<RadioLEDState>(HAL_RadioLEDState::HAL_RadioLED_kOrange));
+
+void RobotController::SetRadioLEDState(RadioLEDState state) {
+  int32_t status = 0;
+  HAL_SetRadioLEDState(static_cast<HAL_RadioLEDState>(state), &status);
+  FRC_CheckErrorStatus(status, "SetRadioLEDState");
+}
+
+RadioLEDState RobotController::GetRadioLEDState() {
+  int32_t status = 0;
+  auto retVal = static_cast<RadioLEDState>(HAL_GetRadioLEDState(&status));
+  FRC_CheckErrorStatus(status, "GetRadioLEDState");
+  return retVal;
+}
+
 CANStatus RobotController::GetCANStatus() {
   int32_t status = 0;
   float percentBusUtilization = 0;
diff --git a/wpilibc/src/main/native/cpp/StadiaController.cpp b/wpilibc/src/main/native/cpp/StadiaController.cpp
new file mode 100644
index 0000000..4f8d666
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/StadiaController.cpp
@@ -0,0 +1,272 @@
+// 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 "frc/StadiaController.h"
+
+#include <hal/FRCUsageReporting.h>
+
+#include "frc/event/BooleanEvent.h"
+
+using namespace frc;
+
+StadiaController::StadiaController(int port) : GenericHID(port) {
+  // re-enable when StadiaController is added to Usage Reporting
+  // HAL_Report(HALUsageReporting::kResourceType_StadiaController, port + 1);
+}
+
+double StadiaController::GetLeftX() const {
+  return GetRawAxis(Axis::kLeftX);
+}
+
+double StadiaController::GetRightX() const {
+  return GetRawAxis(Axis::kRightX);
+}
+
+double StadiaController::GetLeftY() const {
+  return GetRawAxis(Axis::kLeftY);
+}
+
+double StadiaController::GetRightY() const {
+  return GetRawAxis(Axis::kRightY);
+}
+
+bool StadiaController::GetLeftBumper() const {
+  return GetRawButton(Button::kLeftBumper);
+}
+
+bool StadiaController::GetRightBumper() const {
+  return GetRawButton(Button::kRightBumper);
+}
+
+bool StadiaController::GetLeftBumperPressed() {
+  return GetRawButtonPressed(Button::kLeftBumper);
+}
+
+bool StadiaController::GetRightBumperPressed() {
+  return GetRawButtonPressed(Button::kRightBumper);
+}
+
+bool StadiaController::GetLeftBumperReleased() {
+  return GetRawButtonReleased(Button::kLeftBumper);
+}
+
+bool StadiaController::GetRightBumperReleased() {
+  return GetRawButtonReleased(Button::kRightBumper);
+}
+
+BooleanEvent StadiaController::LeftBumper(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetLeftBumper(); });
+}
+
+BooleanEvent StadiaController::RightBumper(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetRightBumper(); });
+}
+
+bool StadiaController::GetLeftStickButton() const {
+  return GetRawButton(Button::kLeftStick);
+}
+
+bool StadiaController::GetRightStickButton() const {
+  return GetRawButton(Button::kRightStick);
+}
+
+bool StadiaController::GetLeftStickButtonPressed() {
+  return GetRawButtonPressed(Button::kLeftStick);
+}
+
+bool StadiaController::GetRightStickButtonPressed() {
+  return GetRawButtonPressed(Button::kRightStick);
+}
+
+bool StadiaController::GetLeftStickButtonReleased() {
+  return GetRawButtonReleased(Button::kLeftStick);
+}
+
+bool StadiaController::GetRightStickButtonReleased() {
+  return GetRawButtonReleased(Button::kRightStick);
+}
+
+BooleanEvent StadiaController::LeftStick(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetLeftStickButton(); });
+}
+
+BooleanEvent StadiaController::RightStick(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetRightStickButton(); });
+}
+
+bool StadiaController::GetAButton() const {
+  return GetRawButton(Button::kA);
+}
+
+bool StadiaController::GetAButtonPressed() {
+  return GetRawButtonPressed(Button::kA);
+}
+
+bool StadiaController::GetAButtonReleased() {
+  return GetRawButtonReleased(Button::kA);
+}
+
+BooleanEvent StadiaController::A(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetAButton(); });
+}
+
+bool StadiaController::GetBButton() const {
+  return GetRawButton(Button::kB);
+}
+
+bool StadiaController::GetBButtonPressed() {
+  return GetRawButtonPressed(Button::kB);
+}
+
+bool StadiaController::GetBButtonReleased() {
+  return GetRawButtonReleased(Button::kB);
+}
+
+BooleanEvent StadiaController::B(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetBButton(); });
+}
+
+bool StadiaController::GetXButton() const {
+  return GetRawButton(Button::kX);
+}
+
+bool StadiaController::GetXButtonPressed() {
+  return GetRawButtonPressed(Button::kX);
+}
+
+bool StadiaController::GetXButtonReleased() {
+  return GetRawButtonReleased(Button::kX);
+}
+
+BooleanEvent StadiaController::X(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetXButton(); });
+}
+
+bool StadiaController::GetYButton() const {
+  return GetRawButton(Button::kY);
+}
+
+bool StadiaController::GetYButtonPressed() {
+  return GetRawButtonPressed(Button::kY);
+}
+
+bool StadiaController::GetYButtonReleased() {
+  return GetRawButtonReleased(Button::kY);
+}
+
+BooleanEvent StadiaController::Y(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetYButton(); });
+}
+
+bool StadiaController::GetEllipsesButton() const {
+  return GetRawButton(Button::kEllipses);
+}
+
+bool StadiaController::GetEllipsesButtonPressed() {
+  return GetRawButtonPressed(Button::kEllipses);
+}
+
+bool StadiaController::GetEllipsesButtonReleased() {
+  return GetRawButtonReleased(Button::kEllipses);
+}
+
+BooleanEvent StadiaController::Ellipses(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetEllipsesButton(); });
+}
+
+bool StadiaController::GetHamburgerButton() const {
+  return GetRawButton(Button::kHamburger);
+}
+
+bool StadiaController::GetHamburgerButtonPressed() {
+  return GetRawButtonPressed(Button::kHamburger);
+}
+
+bool StadiaController::GetHamburgerButtonReleased() {
+  return GetRawButtonReleased(Button::kHamburger);
+}
+
+BooleanEvent StadiaController::Hamburger(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetHamburgerButton(); });
+}
+
+bool StadiaController::GetStadiaButton() const {
+  return GetRawButton(Button::kStadia);
+}
+
+bool StadiaController::GetStadiaButtonPressed() {
+  return GetRawButtonPressed(Button::kStadia);
+}
+
+bool StadiaController::GetStadiaButtonReleased() {
+  return GetRawButtonReleased(Button::kStadia);
+}
+
+BooleanEvent StadiaController::Stadia(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetStadiaButton(); });
+}
+
+bool StadiaController::GetGoogleButton() const {
+  return GetRawButton(Button::kGoogle);
+}
+
+bool StadiaController::GetGoogleButtonPressed() {
+  return GetRawButtonPressed(Button::kGoogle);
+}
+
+bool StadiaController::GetGoogleButtonReleased() {
+  return GetRawButtonReleased(Button::kGoogle);
+}
+
+BooleanEvent StadiaController::Google(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetGoogleButton(); });
+}
+
+bool StadiaController::GetFrameButton() const {
+  return GetRawButton(Button::kFrame);
+}
+
+bool StadiaController::GetFrameButtonPressed() {
+  return GetRawButtonPressed(Button::kFrame);
+}
+
+bool StadiaController::GetFrameButtonReleased() {
+  return GetRawButtonReleased(Button::kFrame);
+}
+
+BooleanEvent StadiaController::Frame(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetFrameButton(); });
+}
+
+bool StadiaController::GetLeftTriggerButton() const {
+  return GetRawButton(Button::kLeftTrigger);
+}
+
+bool StadiaController::GetLeftTriggerButtonPressed() {
+  return GetRawButtonPressed(Button::kLeftTrigger);
+}
+
+bool StadiaController::GetLeftTriggerButtonReleased() {
+  return GetRawButtonReleased(Button::kLeftTrigger);
+}
+
+BooleanEvent StadiaController::LeftTrigger(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetLeftTriggerButton(); });
+}
+
+bool StadiaController::GetRightTriggerButton() const {
+  return GetRawButton(Button::kRightTrigger);
+}
+
+bool StadiaController::GetRightTriggerButtonPressed() {
+  return GetRawButtonPressed(Button::kRightTrigger);
+}
+
+bool StadiaController::GetRightTriggerButtonReleased() {
+  return GetRawButtonReleased(Button::kRightTrigger);
+}
+
+BooleanEvent StadiaController::RightTrigger(EventLoop* loop) const {
+  return BooleanEvent(loop, [this]() { return this->GetRightTriggerButton(); });
+}
diff --git a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp
index 8cce62e..e3a0a8c 100644
--- a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp
+++ b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp
@@ -16,11 +16,21 @@
 
 using namespace frc;
 
+WPI_IGNORE_DEPRECATED
+
 DifferentialDrive::DifferentialDrive(MotorController& leftMotor,
                                      MotorController& rightMotor)
-    : m_leftMotor(&leftMotor), m_rightMotor(&rightMotor) {
-  wpi::SendableRegistry::AddChild(this, m_leftMotor);
-  wpi::SendableRegistry::AddChild(this, m_rightMotor);
+    : DifferentialDrive{[&](double output) { leftMotor.Set(output); },
+                        [&](double output) { rightMotor.Set(output); }} {
+  wpi::SendableRegistry::AddChild(this, &leftMotor);
+  wpi::SendableRegistry::AddChild(this, &rightMotor);
+}
+
+WPI_UNIGNORE_DEPRECATED
+
+DifferentialDrive::DifferentialDrive(std::function<void(double)> leftMotor,
+                                     std::function<void(double)> rightMotor)
+    : m_leftMotor{std::move(leftMotor)}, m_rightMotor{std::move(rightMotor)} {
   static int instances = 0;
   ++instances;
   wpi::SendableRegistry::AddLW(this, "DifferentialDrive", instances);
@@ -40,8 +50,11 @@
 
   auto [left, right] = ArcadeDriveIK(xSpeed, zRotation, squareInputs);
 
-  m_leftMotor->Set(left);
-  m_rightMotor->Set(right);
+  m_leftOutput = left * m_maxOutput;
+  m_rightOutput = right * m_maxOutput;
+
+  m_leftMotor(m_leftOutput);
+  m_rightMotor(m_rightOutput);
 
   Feed();
 }
@@ -60,8 +73,11 @@
 
   auto [left, right] = CurvatureDriveIK(xSpeed, zRotation, allowTurnInPlace);
 
-  m_leftMotor->Set(left * m_maxOutput);
-  m_rightMotor->Set(right * m_maxOutput);
+  m_leftOutput = left * m_maxOutput;
+  m_rightOutput = right * m_maxOutput;
+
+  m_leftMotor(m_leftOutput);
+  m_rightMotor(m_rightOutput);
 
   Feed();
 }
@@ -80,8 +96,11 @@
 
   auto [left, right] = TankDriveIK(leftSpeed, rightSpeed, squareInputs);
 
-  m_leftMotor->Set(left * m_maxOutput);
-  m_rightMotor->Set(right * m_maxOutput);
+  m_leftOutput = left * m_maxOutput;
+  m_rightOutput = right * m_maxOutput;
+
+  m_leftMotor(m_leftOutput);
+  m_rightMotor(m_rightOutput);
 
   Feed();
 }
@@ -157,8 +176,12 @@
 }
 
 void DifferentialDrive::StopMotor() {
-  m_leftMotor->StopMotor();
-  m_rightMotor->StopMotor();
+  m_leftOutput = 0.0;
+  m_rightOutput = 0.0;
+
+  m_leftMotor(0.0);
+  m_rightMotor(0.0);
+
   Feed();
 }
 
@@ -171,9 +194,7 @@
   builder.SetActuator(true);
   builder.SetSafeState([=, this] { StopMotor(); });
   builder.AddDoubleProperty(
-      "Left Motor Speed", [=, this] { return m_leftMotor->Get(); },
-      [=, this](double value) { m_leftMotor->Set(value); });
+      "Left Motor Speed", [&] { return m_leftOutput; }, m_leftMotor);
   builder.AddDoubleProperty(
-      "Right Motor Speed", [=, this] { return m_rightMotor->Get(); },
-      [=, this](double value) { m_rightMotor->Set(value); });
+      "Right Motor Speed", [&] { return m_rightOutput; }, m_rightMotor);
 }
diff --git a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp
index 2bf6a3f..aeec27d 100644
--- a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp
+++ b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp
@@ -16,18 +16,32 @@
 
 using namespace frc;
 
+WPI_IGNORE_DEPRECATED
+
 MecanumDrive::MecanumDrive(MotorController& frontLeftMotor,
                            MotorController& rearLeftMotor,
                            MotorController& frontRightMotor,
                            MotorController& rearRightMotor)
-    : m_frontLeftMotor(&frontLeftMotor),
-      m_rearLeftMotor(&rearLeftMotor),
-      m_frontRightMotor(&frontRightMotor),
-      m_rearRightMotor(&rearRightMotor) {
-  wpi::SendableRegistry::AddChild(this, m_frontLeftMotor);
-  wpi::SendableRegistry::AddChild(this, m_rearLeftMotor);
-  wpi::SendableRegistry::AddChild(this, m_frontRightMotor);
-  wpi::SendableRegistry::AddChild(this, m_rearRightMotor);
+    : MecanumDrive{[&](double output) { frontLeftMotor.Set(output); },
+                   [&](double output) { rearLeftMotor.Set(output); },
+                   [&](double output) { frontRightMotor.Set(output); },
+                   [&](double output) { rearRightMotor.Set(output); }} {
+  wpi::SendableRegistry::AddChild(this, &frontLeftMotor);
+  wpi::SendableRegistry::AddChild(this, &rearLeftMotor);
+  wpi::SendableRegistry::AddChild(this, &frontRightMotor);
+  wpi::SendableRegistry::AddChild(this, &rearRightMotor);
+}
+
+WPI_UNIGNORE_DEPRECATED
+
+MecanumDrive::MecanumDrive(std::function<void(double)> frontLeftMotor,
+                           std::function<void(double)> rearLeftMotor,
+                           std::function<void(double)> frontRightMotor,
+                           std::function<void(double)> rearRightMotor)
+    : m_frontLeftMotor{std::move(frontLeftMotor)},
+      m_rearLeftMotor{std::move(rearLeftMotor)},
+      m_frontRightMotor{std::move(frontRightMotor)},
+      m_rearRightMotor{std::move(rearRightMotor)} {
   static int instances = 0;
   ++instances;
   wpi::SendableRegistry::AddLW(this, "MecanumDrive", instances);
@@ -47,10 +61,15 @@
   auto [frontLeft, frontRight, rearLeft, rearRight] =
       DriveCartesianIK(xSpeed, ySpeed, zRotation, gyroAngle);
 
-  m_frontLeftMotor->Set(frontLeft * m_maxOutput);
-  m_frontRightMotor->Set(frontRight * m_maxOutput);
-  m_rearLeftMotor->Set(rearLeft * m_maxOutput);
-  m_rearRightMotor->Set(rearRight * m_maxOutput);
+  m_frontLeftOutput = frontLeft * m_maxOutput;
+  m_rearLeftOutput = rearLeft * m_maxOutput;
+  m_frontRightOutput = frontRight * m_maxOutput;
+  m_rearRightOutput = rearRight * m_maxOutput;
+
+  m_frontLeftMotor(m_frontLeftOutput);
+  m_frontRightMotor(m_frontRightOutput);
+  m_rearLeftMotor(m_rearLeftOutput);
+  m_rearRightMotor(m_rearRightOutput);
 
   Feed();
 }
@@ -68,10 +87,16 @@
 }
 
 void MecanumDrive::StopMotor() {
-  m_frontLeftMotor->StopMotor();
-  m_frontRightMotor->StopMotor();
-  m_rearLeftMotor->StopMotor();
-  m_rearRightMotor->StopMotor();
+  m_frontLeftOutput = 0.0;
+  m_frontRightOutput = 0.0;
+  m_rearLeftOutput = 0.0;
+  m_rearRightOutput = 0.0;
+
+  m_frontLeftMotor(0.0);
+  m_frontRightMotor(0.0);
+  m_rearLeftMotor(0.0);
+  m_rearRightMotor(0.0);
+
   Feed();
 }
 
@@ -108,15 +133,15 @@
   builder.SetActuator(true);
   builder.SetSafeState([=, this] { StopMotor(); });
   builder.AddDoubleProperty(
-      "Front Left Motor Speed", [=, this] { return m_frontLeftMotor->Get(); },
-      [=, this](double value) { m_frontLeftMotor->Set(value); });
+      "Front Left Motor Speed", [&] { return m_frontLeftOutput; },
+      m_frontLeftMotor);
   builder.AddDoubleProperty(
-      "Front Right Motor Speed", [=, this] { return m_frontRightMotor->Get(); },
-      [=, this](double value) { m_frontRightMotor->Set(value); });
+      "Front Right Motor Speed", [&] { return m_frontRightOutput; },
+      m_frontRightMotor);
   builder.AddDoubleProperty(
-      "Rear Left Motor Speed", [=, this] { return m_rearLeftMotor->Get(); },
-      [=, this](double value) { m_rearLeftMotor->Set(value); });
+      "Rear Left Motor Speed", [&] { return m_rearLeftOutput; },
+      m_rearLeftMotor);
   builder.AddDoubleProperty(
-      "Rear Right Motor Speed", [=, this] { return m_rearRightMotor->Get(); },
-      [=, this](double value) { m_rearRightMotor->Set(value); });
+      "Rear Right Motor Speed", [&] { return m_rearRightOutput; },
+      m_rearRightMotor);
 }
diff --git a/wpilibc/src/main/native/cpp/event/EventLoop.cpp b/wpilibc/src/main/native/cpp/event/EventLoop.cpp
index 5af79c9..c85286b 100644
--- a/wpilibc/src/main/native/cpp/event/EventLoop.cpp
+++ b/wpilibc/src/main/native/cpp/event/EventLoop.cpp
@@ -4,20 +4,41 @@
 
 #include "frc/event/EventLoop.h"
 
+#include "frc/Errors.h"
+
 using namespace frc;
 
+namespace {
+struct RunningSetter {
+  bool& m_running;
+  explicit RunningSetter(bool& running) noexcept : m_running{running} {
+    m_running = true;
+  }
+  ~RunningSetter() noexcept { m_running = false; }
+};
+}  // namespace
+
 EventLoop::EventLoop() {}
 
 void EventLoop::Bind(wpi::unique_function<void()> action) {
+  if (m_running) {
+    throw FRC_MakeError(err::Error,
+                        "Cannot bind EventLoop while it is running");
+  }
   m_bindings.emplace_back(std::move(action));
 }
 
 void EventLoop::Poll() {
+  RunningSetter runSetter{m_running};
   for (wpi::unique_function<void()>& action : m_bindings) {
     action();
   }
 }
 
 void EventLoop::Clear() {
+  if (m_running) {
+    throw FRC_MakeError(err::Error,
+                        "Cannot clear EventLoop while it is running");
+  }
   m_bindings.clear();
 }
diff --git a/wpilibc/src/main/native/cpp/internal/DriverStationModeThread.cpp b/wpilibc/src/main/native/cpp/internal/DriverStationModeThread.cpp
index 4085658..78d580e 100644
--- a/wpilibc/src/main/native/cpp/internal/DriverStationModeThread.cpp
+++ b/wpilibc/src/main/native/cpp/internal/DriverStationModeThread.cpp
@@ -23,13 +23,14 @@
   }
 }
 
-void DriverStationModeThread::InAutonomous(bool entering) {
-  m_userInAutonomous = entering;
-}
 void DriverStationModeThread::InDisabled(bool entering) {
   m_userInDisabled = entering;
 }
 
+void DriverStationModeThread::InAutonomous(bool entering) {
+  m_userInAutonomous = entering;
+}
+
 void DriverStationModeThread::InTeleop(bool entering) {
   m_userInTeleop = entering;
 }
diff --git a/wpilibc/src/main/native/cpp/motorcontrol/MotorController.cpp b/wpilibc/src/main/native/cpp/motorcontrol/MotorController.cpp
index 9d20144..2b64da2 100644
--- a/wpilibc/src/main/native/cpp/motorcontrol/MotorController.cpp
+++ b/wpilibc/src/main/native/cpp/motorcontrol/MotorController.cpp
@@ -9,5 +9,6 @@
 using namespace frc;
 
 void MotorController::SetVoltage(units::volt_t output) {
+  // NOLINTNEXTLINE(bugprone-integer-division)
   Set(output / RobotController::GetBatteryVoltage());
 }
diff --git a/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp b/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp
index f855d14..cf57f7c 100644
--- a/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp
+++ b/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp
@@ -12,6 +12,8 @@
 // Can't use a delegated constructor here because of an MSVC bug.
 // https://developercommunity.visualstudio.com/content/problem/583/compiler-bug-with-delegating-a-constructor.html
 
+WPI_IGNORE_DEPRECATED
+
 MotorControllerGroup::MotorControllerGroup(
     std::vector<std::reference_wrapper<MotorController>>&& motorControllers)
     : m_motorControllers(std::move(motorControllers)) {
@@ -74,3 +76,5 @@
       "Value", [=, this] { return Get(); },
       [=, this](double value) { Set(value); });
 }
+
+WPI_UNIGNORE_DEPRECATED
diff --git a/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp b/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp
index f25aa91..a05b7cc 100644
--- a/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp
+++ b/wpilibc/src/main/native/cpp/motorcontrol/NidecBrushless.cpp
@@ -11,6 +11,8 @@
 
 using namespace frc;
 
+WPI_IGNORE_DEPRECATED
+
 NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel)
     : m_dio(dioChannel), m_pwm(pwmChannel) {
   wpi::SendableRegistry::AddChild(this, &m_dio);
@@ -26,6 +28,8 @@
   wpi::SendableRegistry::AddLW(this, "Nidec Brushless", pwmChannel);
 }
 
+WPI_UNIGNORE_DEPRECATED
+
 void NidecBrushless::Set(double speed) {
   if (!m_disabled) {
     m_speed = speed;
diff --git a/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp b/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp
index 3692f75..924e4fd 100644
--- a/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp
+++ b/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp
@@ -8,13 +8,31 @@
 #include <wpi/sendable/SendableBuilder.h>
 #include <wpi/sendable/SendableRegistry.h>
 
+#include "frc/RobotController.h"
+
 using namespace frc;
 
 void PWMMotorController::Set(double speed) {
-  m_pwm.SetSpeed(m_isInverted ? -speed : speed);
+  if (m_isInverted) {
+    speed = -speed;
+  }
+  m_pwm.SetSpeed(speed);
+
+  for (auto& follower : m_nonowningFollowers) {
+    follower->Set(speed);
+  }
+  for (auto& follower : m_owningFollowers) {
+    follower->Set(speed);
+  }
+
   Feed();
 }
 
+void PWMMotorController::SetVoltage(units::volt_t output) {
+  // NOLINTNEXTLINE(bugprone-integer-division)
+  Set(output / RobotController::GetBatteryVoltage());
+}
+
 double PWMMotorController::Get() const {
   return m_pwm.GetSpeed() * (m_isInverted ? -1.0 : 1.0);
 }
@@ -48,11 +66,19 @@
   m_pwm.EnableDeadbandElimination(eliminateDeadband);
 }
 
+void PWMMotorController::AddFollower(PWMMotorController& follower) {
+  m_nonowningFollowers.emplace_back(&follower);
+}
+
+WPI_IGNORE_DEPRECATED
+
 PWMMotorController::PWMMotorController(std::string_view name, int channel)
     : m_pwm(channel, false) {
   wpi::SendableRegistry::AddLW(this, name, channel);
 }
 
+WPI_UNIGNORE_DEPRECATED
+
 void PWMMotorController::InitSendable(wpi::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Motor Controller");
   builder.SetActuator(true);
diff --git a/wpilibc/src/main/native/cpp/motorcontrol/PWMSparkFlex.cpp b/wpilibc/src/main/native/cpp/motorcontrol/PWMSparkFlex.cpp
new file mode 100644
index 0000000..945a70e
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/motorcontrol/PWMSparkFlex.cpp
@@ -0,0 +1,20 @@
+// 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 "frc/motorcontrol/PWMSparkFlex.h"
+
+#include <hal/FRCUsageReporting.h>
+
+using namespace frc;
+
+PWMSparkFlex::PWMSparkFlex(int channel)
+    : PWMMotorController("PWMSparkFlex", channel) {
+  m_pwm.SetBounds(2.003_ms, 1.55_ms, 1.50_ms, 1.46_ms, 0.999_ms);
+  m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
+  m_pwm.SetSpeed(0.0);
+  m_pwm.SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_RevSparkFlexPWM,
+             GetChannel() + 1);
+}
diff --git a/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardInstance.cpp b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardInstance.cpp
index a19cc6a..8c0880a 100644
--- a/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardInstance.cpp
+++ b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardInstance.cpp
@@ -30,12 +30,17 @@
   m_impl->selectedTabPub =
       m_impl->rootMetaTable->GetStringTopic("Selected")
           .Publish(nt::PubSubOptions{.keepDuplicates = true});
-  HAL_Report(HALUsageReporting::kResourceType_Shuffleboard, 0);
 }
 
 ShuffleboardInstance::~ShuffleboardInstance() = default;
 
+static bool gReported = false;
+
 frc::ShuffleboardTab& ShuffleboardInstance::GetTab(std::string_view title) {
+  if (!gReported) {
+    HAL_Report(HALUsageReporting::kResourceType_Shuffleboard, 0);
+    gReported = true;
+  }
   if (m_impl->tabs.find(title) == m_impl->tabs.end()) {
     m_impl->tabs.try_emplace(title,
                              std::make_unique<ShuffleboardTab>(*this, title));
diff --git a/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp b/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp
index 8c27cdf..d5addb2 100644
--- a/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp
+++ b/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp
@@ -58,7 +58,7 @@
 }
 
 void DifferentialDrivetrainSim::Update(units::second_t dt) {
-  m_x = RK4([this](auto& x, auto& u) { return Dynamics(x, u); }, m_x, m_u, dt);
+  m_x = RKDP([this](auto& x, auto& u) { return Dynamics(x, u); }, m_x, m_u, dt);
   m_y = m_x + frc::MakeWhiteNoiseVector<7>(m_measurementStdDevs);
 }
 
@@ -92,26 +92,22 @@
 }
 
 units::ampere_t DifferentialDrivetrainSim::GetLeftCurrentDraw() const {
-  auto loadIleft =
-      m_motor.Current(
-          units::radians_per_second_t{m_x(State::kLeftVelocity) *
-                                      m_currentGearing / m_wheelRadius.value()},
-          units::volt_t{m_u(0)}) *
-      wpi::sgn(m_u(0));
-
-  return loadIleft;
+  return m_motor.Current(units::radians_per_second_t{m_x(State::kLeftVelocity) *
+                                                     m_currentGearing /
+                                                     m_wheelRadius.value()},
+                         units::volt_t{m_u(0)}) *
+         wpi::sgn(m_u(0));
 }
 
 units::ampere_t DifferentialDrivetrainSim::GetRightCurrentDraw() const {
-  auto loadIRight =
-      m_motor.Current(
-          units::radians_per_second_t{m_x(State::kRightVelocity) *
-                                      m_currentGearing / m_wheelRadius.value()},
-          units::volt_t{m_u(1)}) *
-      wpi::sgn(m_u(1));
-
-  return loadIRight;
+  return m_motor.Current(
+             units::radians_per_second_t{m_x(State::kRightVelocity) *
+                                         m_currentGearing /
+                                         m_wheelRadius.value()},
+             units::volt_t{m_u(1)}) *
+         wpi::sgn(m_u(1));
 }
+
 units::ampere_t DifferentialDrivetrainSim::GetCurrentDraw() const {
   return GetLeftCurrentDraw() + GetRightCurrentDraw();
 }
diff --git a/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp b/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp
index 476d07a..04aef3a 100644
--- a/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp
+++ b/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp
@@ -12,11 +12,6 @@
 using namespace frc;
 using namespace frc::sim;
 
-PneumaticsBaseSim::PneumaticsBaseSim(int module) : m_index{module} {}
-
-PneumaticsBaseSim::PneumaticsBaseSim(const PneumaticsBase& module)
-    : m_index{module.GetModuleNumber()} {}
-
 std::shared_ptr<PneumaticsBaseSim> PneumaticsBaseSim::GetForType(
     int module, PneumaticsModuleType type) {
   switch (type) {
@@ -31,3 +26,8 @@
                           static_cast<int>(module));
   }
 }
+
+PneumaticsBaseSim::PneumaticsBaseSim(int module) : m_index{module} {}
+
+PneumaticsBaseSim::PneumaticsBaseSim(const PneumaticsBase& module)
+    : m_index{module.GetModuleNumber()} {}
diff --git a/wpilibc/src/main/native/cpp/simulation/RoboRioSim.cpp b/wpilibc/src/main/native/cpp/simulation/RoboRioSim.cpp
index 90d9651..728d358 100644
--- a/wpilibc/src/main/native/cpp/simulation/RoboRioSim.cpp
+++ b/wpilibc/src/main/native/cpp/simulation/RoboRioSim.cpp
@@ -338,6 +338,23 @@
   HALSIM_SetRoboRioComments(comments.data(), comments.size());
 }
 
+std::unique_ptr<CallbackStore> RoboRioSim::RegisterRadioLEDStateCallback(
+    NotifyCallback callback, bool initialNotify) {
+  auto store = std::make_unique<CallbackStore>(
+      -1, callback, &HALSIM_CancelRoboRioRadioLEDStateCallback);
+  store->SetUid(HALSIM_RegisterRoboRioRadioLEDStateCallback(
+      &CallbackStoreThunk, store.get(), initialNotify));
+  return store;
+}
+
+RadioLEDState RoboRioSim::GetRadioLEDState() {
+  return static_cast<RadioLEDState>(HALSIM_GetRoboRioRadioLEDState());
+}
+
+void RoboRioSim::SetRadioLEDState(RadioLEDState state) {
+  HALSIM_SetRoboRioRadioLEDState(static_cast<HAL_RadioLEDState>(state));
+}
+
 void RoboRioSim::ResetData() {
   HALSIM_ResetRoboRioData();
 }
diff --git a/wpilibc/src/main/native/cpp/simulation/UltrasonicSim.cpp b/wpilibc/src/main/native/cpp/simulation/UltrasonicSim.cpp
index 30a5650..1016c4b 100644
--- a/wpilibc/src/main/native/cpp/simulation/UltrasonicSim.cpp
+++ b/wpilibc/src/main/native/cpp/simulation/UltrasonicSim.cpp
@@ -18,8 +18,8 @@
   m_simRange = deviceSim.GetDouble("Range (in)");
 }
 
-void UltrasonicSim::SetRangeValid(bool isValid) {
-  m_simRangeValid.Set(isValid);
+void UltrasonicSim::SetRangeValid(bool valid) {
+  m_simRangeValid.Set(valid);
 }
 
 void UltrasonicSim::SetRange(units::inch_t range) {
diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp
index e6991d4..d57473f 100644
--- a/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp
+++ b/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp
@@ -19,8 +19,6 @@
 
 namespace {
 struct Instance {
-  Instance() { HAL_Report(HALUsageReporting::kResourceType_SmartDashboard, 0); }
-
   detail::ListenerExecutor listenerExecutor;
   std::shared_ptr<nt::NetworkTable> table =
       nt::NetworkTableInstance::GetDefault().GetTable("SmartDashboard");
@@ -46,6 +44,8 @@
 }  // namespace frc::impl
 #endif
 
+static bool gReported = false;
+
 void SmartDashboard::init() {
   GetInstance();
 }
@@ -59,18 +59,23 @@
 }
 
 void SmartDashboard::SetPersistent(std::string_view key) {
-  GetInstance().table->GetEntry(key).SetPersistent();
+  GetEntry(key).SetPersistent();
 }
 
 void SmartDashboard::ClearPersistent(std::string_view key) {
-  GetInstance().table->GetEntry(key).ClearPersistent();
+  GetEntry(key).ClearPersistent();
 }
 
 bool SmartDashboard::IsPersistent(std::string_view key) {
-  return GetInstance().table->GetEntry(key).IsPersistent();
+  return GetEntry(key).IsPersistent();
 }
 
 nt::NetworkTableEntry SmartDashboard::GetEntry(std::string_view key) {
+  if (!gReported) {
+    HAL_Report(HALUsageReporting::kResourceType_SmartDashboard,
+               HALUsageReporting::kSmartDashboard_Instance);
+    gReported = true;
+  }
   return GetInstance().table->GetEntry(key);
 }
 
@@ -78,6 +83,11 @@
   if (!data) {
     throw FRC_MakeError(err::NullParameter, "value");
   }
+  if (!gReported) {
+    HAL_Report(HALUsageReporting::kResourceType_SmartDashboard,
+               HALUsageReporting::kSmartDashboard_Instance);
+    gReported = true;
+  }
   auto& inst = GetInstance();
   std::scoped_lock lock(inst.tablesToDataMutex);
   auto& uid = inst.tablesToData[key];
@@ -120,7 +130,7 @@
 
 bool SmartDashboard::SetDefaultBoolean(std::string_view key,
                                        bool defaultValue) {
-  return GetInstance().table->GetEntry(key).SetDefaultBoolean(defaultValue);
+  return GetEntry(key).SetDefaultBoolean(defaultValue);
 }
 
 bool SmartDashboard::GetBoolean(std::string_view keyName, bool defaultValue) {
@@ -133,7 +143,7 @@
 
 bool SmartDashboard::SetDefaultNumber(std::string_view key,
                                       double defaultValue) {
-  return GetInstance().table->GetEntry(key).SetDefaultDouble(defaultValue);
+  return GetEntry(key).SetDefaultDouble(defaultValue);
 }
 
 double SmartDashboard::GetNumber(std::string_view keyName,
@@ -148,7 +158,7 @@
 
 bool SmartDashboard::SetDefaultString(std::string_view key,
                                       std::string_view defaultValue) {
-  return GetInstance().table->GetEntry(key).SetDefaultString(defaultValue);
+  return GetEntry(key).SetDefaultString(defaultValue);
 }
 
 std::string SmartDashboard::GetString(std::string_view keyName,
@@ -158,63 +168,62 @@
 
 bool SmartDashboard::PutBooleanArray(std::string_view key,
                                      std::span<const int> value) {
-  return GetInstance().table->GetEntry(key).SetBooleanArray(value);
+  return GetEntry(key).SetBooleanArray(value);
 }
 
 bool SmartDashboard::SetDefaultBooleanArray(std::string_view key,
                                             std::span<const int> defaultValue) {
-  return GetInstance().table->GetEntry(key).SetDefaultBooleanArray(
-      defaultValue);
+  return GetEntry(key).SetDefaultBooleanArray(defaultValue);
 }
 
 std::vector<int> SmartDashboard::GetBooleanArray(
     std::string_view key, std::span<const int> defaultValue) {
-  return GetInstance().table->GetEntry(key).GetBooleanArray(defaultValue);
+  return GetEntry(key).GetBooleanArray(defaultValue);
 }
 
 bool SmartDashboard::PutNumberArray(std::string_view key,
                                     std::span<const double> value) {
-  return GetInstance().table->GetEntry(key).SetDoubleArray(value);
+  return GetEntry(key).SetDoubleArray(value);
 }
 
 bool SmartDashboard::SetDefaultNumberArray(
     std::string_view key, std::span<const double> defaultValue) {
-  return GetInstance().table->GetEntry(key).SetDefaultDoubleArray(defaultValue);
+  return GetEntry(key).SetDefaultDoubleArray(defaultValue);
 }
 
 std::vector<double> SmartDashboard::GetNumberArray(
     std::string_view key, std::span<const double> defaultValue) {
-  return GetInstance().table->GetEntry(key).GetDoubleArray(defaultValue);
+  return GetEntry(key).GetDoubleArray(defaultValue);
 }
 
 bool SmartDashboard::PutStringArray(std::string_view key,
                                     std::span<const std::string> value) {
-  return GetInstance().table->GetEntry(key).SetStringArray(value);
+  return GetEntry(key).SetStringArray(value);
 }
 
 bool SmartDashboard::SetDefaultStringArray(
     std::string_view key, std::span<const std::string> defaultValue) {
-  return GetInstance().table->GetEntry(key).SetDefaultStringArray(defaultValue);
+  return GetEntry(key).SetDefaultStringArray(defaultValue);
 }
 
 std::vector<std::string> SmartDashboard::GetStringArray(
     std::string_view key, std::span<const std::string> defaultValue) {
-  return GetInstance().table->GetEntry(key).GetStringArray(defaultValue);
+  return GetEntry(key).GetStringArray(defaultValue);
 }
 
 bool SmartDashboard::PutRaw(std::string_view key,
                             std::span<const uint8_t> value) {
-  return GetInstance().table->GetEntry(key).SetRaw(value);
+  return GetEntry(key).SetRaw(value);
 }
 
 bool SmartDashboard::SetDefaultRaw(std::string_view key,
                                    std::span<const uint8_t> defaultValue) {
-  return GetInstance().table->GetEntry(key).SetDefaultRaw(defaultValue);
+  return GetEntry(key).SetDefaultRaw(defaultValue);
 }
 
 std::vector<uint8_t> SmartDashboard::GetRaw(
     std::string_view key, std::span<const uint8_t> defaultValue) {
-  return GetInstance().table->GetEntry(key).GetRaw(defaultValue);
+  return GetEntry(key).GetRaw(defaultValue);
 }
 
 bool SmartDashboard::PutValue(std::string_view keyName,
@@ -224,7 +233,7 @@
 
 bool SmartDashboard::SetDefaultValue(std::string_view key,
                                      const nt::Value& defaultValue) {
-  return GetInstance().table->GetEntry(key).SetDefaultValue(defaultValue);
+  return GetEntry(key).SetDefaultValue(defaultValue);
 }
 
 nt::Value SmartDashboard::GetValue(std::string_view keyName) {
diff --git a/wpilibc/src/main/native/cpp/sysid/SysIdRoutineLog.cpp b/wpilibc/src/main/native/cpp/sysid/SysIdRoutineLog.cpp
new file mode 100644
index 0000000..b99b792
--- /dev/null
+++ b/wpilibc/src/main/native/cpp/sysid/SysIdRoutineLog.cpp
@@ -0,0 +1,66 @@
+// 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 "frc/sysid/SysIdRoutineLog.h"
+
+#include <fmt/format.h>
+
+#include "frc/DataLogManager.h"
+
+using namespace frc::sysid;
+
+SysIdRoutineLog::SysIdRoutineLog(std::string_view logName)
+    : m_logName(logName),
+      m_state(wpi::log::StringLogEntry{
+          frc::DataLogManager::GetLog(),
+          fmt::format("sysid-test-state{}", logName)}) {
+  m_state.Append(StateEnumToString(State::kNone));
+}
+
+SysIdRoutineLog::MotorLog::MotorLog(std::string_view motorName,
+                                    std::string_view logName,
+                                    LogEntries* logEntries)
+    : m_motorName(motorName), m_logName(logName), m_logEntries(logEntries) {
+  (*logEntries)[motorName] = MotorEntries();
+}
+
+SysIdRoutineLog::MotorLog& SysIdRoutineLog::MotorLog::value(
+    std::string_view name, double value, std::string_view unit) {
+  auto& motorEntries = (*m_logEntries)[m_motorName];
+
+  if (!motorEntries.contains(name)) {
+    wpi::log::DataLog& log = frc::DataLogManager::GetLog();
+
+    motorEntries[name] = wpi::log::DoubleLogEntry(
+        log, fmt::format("{}-{}-{}", name, m_motorName, m_logName), unit);
+  }
+
+  motorEntries[name].Append(value);
+  return *this;
+}
+
+SysIdRoutineLog::MotorLog SysIdRoutineLog::Motor(std::string_view motorName) {
+  return MotorLog{motorName, m_logName, &m_logEntries};
+}
+
+void SysIdRoutineLog::RecordState(State state) {
+  m_state.Append(StateEnumToString(state));
+}
+
+std::string SysIdRoutineLog::StateEnumToString(State state) {
+  switch (state) {
+    case State::kQuasistaticForward:
+      return "quasistatic-forward";
+    case State::kQuasistaticReverse:
+      return "quasistatic-reverse";
+    case State::kDynamicForward:
+      return "dynamic-forward";
+    case State::kDynamicReverse:
+      return "dynamic-reverse";
+    case State::kNone:
+      return "none";
+    default:
+      return "none";
+  }
+}
diff --git a/wpilibc/src/main/native/cpp/util/Color.cpp b/wpilibc/src/main/native/cpp/util/Color.cpp
deleted file mode 100644
index e3adaf2..0000000
--- a/wpilibc/src/main/native/cpp/util/Color.cpp
+++ /dev/null
@@ -1,15 +0,0 @@
-// 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 "frc/util/Color.h"
-
-#include <fmt/format.h>
-
-using namespace frc;
-
-std::string Color::HexString() const {
-  return fmt::format("#{:02X}{:02X}{:02X}", static_cast<int>(255.0 * red),
-                     static_cast<int>(255.0 * green),
-                     static_cast<int>(255.0 * blue));
-}
diff --git a/wpilibc/src/main/native/cpp/util/Color8Bit.cpp b/wpilibc/src/main/native/cpp/util/Color8Bit.cpp
deleted file mode 100644
index af200a2..0000000
--- a/wpilibc/src/main/native/cpp/util/Color8Bit.cpp
+++ /dev/null
@@ -1,13 +0,0 @@
-// 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 "frc/util/Color8Bit.h"
-
-#include <fmt/format.h>
-
-using namespace frc;
-
-std::string Color8Bit::HexString() const {
-  return fmt::format("#{:02X}{:02X}{:02X}", red, green, blue);
-}
diff --git a/wpilibc/src/main/native/include/frc/ADIS16448_IMU.h b/wpilibc/src/main/native/include/frc/ADIS16448_IMU.h
index 3f4a1c2..41c66c1 100644
--- a/wpilibc/src/main/native/include/frc/ADIS16448_IMU.h
+++ b/wpilibc/src/main/native/include/frc/ADIS16448_IMU.h
@@ -56,23 +56,47 @@
 class ADIS16448_IMU : public wpi::Sendable,
                       public wpi::SendableHelper<ADIS16448_IMU> {
  public:
-  /* ADIS16448 Calibration Time Enum Class */
+  /**
+   * ADIS16448 calibration times.
+   */
   enum class CalibrationTime {
+    /// 32 ms calibration time.
     _32ms = 0,
+    /// 64 ms calibration time.
     _64ms = 1,
+    /// 128 ms calibration time.
     _128ms = 2,
+    /// 256 ms calibration time.
     _256ms = 3,
+    /// 512 ms calibration time.
     _512ms = 4,
+    /// 1 s calibration time.
     _1s = 5,
+    /// 2 s calibration time.
     _2s = 6,
+    /// 4 s calibration time.
     _4s = 7,
+    /// 8 s calibration time.
     _8s = 8,
+    /// 16 s calibration time.
     _16s = 9,
+    /// 32 s calibration time.
     _32s = 10,
+    /// 64 s calibration time.
     _64s = 11
   };
 
-  enum IMUAxis { kX, kY, kZ };
+  /**
+   * IMU axes.
+   */
+  enum IMUAxis {
+    /// The IMU's X axis.
+    kX,
+    /// The IMU's Y axis.
+    kY,
+    /// The IMU's Z axis.
+    kZ
+  };
 
   /**
    * IMU constructor on onboard MXP CS0, Z-up orientation, and complementary
@@ -183,31 +207,71 @@
    */
   units::meters_per_second_squared_t GetAccelZ() const;
 
+  /**
+   * Returns the complementary angle around the X axis computed from
+   * accelerometer and gyro rate measurements.
+   */
   units::degree_t GetXComplementaryAngle() const;
 
+  /**
+   * Returns the complementary angle around the Y axis computed from
+   * accelerometer and gyro rate measurements.
+   */
   units::degree_t GetYComplementaryAngle() const;
 
+  /**
+   * Returns the X-axis filtered acceleration angle.
+   */
   units::degree_t GetXFilteredAccelAngle() const;
 
+  /**
+   * Returns the Y-axis filtered acceleration angle.
+   */
   units::degree_t GetYFilteredAccelAngle() const;
 
+  /**
+   * Returns the magnetic field strength in the X axis.
+   */
   units::tesla_t GetMagneticFieldX() const;
 
+  /**
+   * Returns the magnetic field strength in the Y axis.
+   */
   units::tesla_t GetMagneticFieldY() const;
 
+  /**
+   * Returns the magnetic field strength in the Z axis.
+   */
   units::tesla_t GetMagneticFieldZ() const;
 
+  /**
+   * Returns the barometric pressure.
+   */
   units::pounds_per_square_inch_t GetBarometricPressure() const;
 
+  /**
+   * Returns the temperature.
+   */
   units::celsius_t GetTemperature() const;
 
   IMUAxis GetYawAxis() const;
 
   int SetYawAxis(IMUAxis yaw_axis);
 
+  /**
+   * Checks the connection status of the IMU.
+   *
+   * @return True if the IMU is connected, false otherwise.
+   */
   bool IsConnected() const;
 
-  int ConfigDecRate(uint16_t DecimationRate);
+  /**
+   * Configures the decimation rate of the IMU.
+   *
+   * @param decimationRate The new decimation value.
+   * @return 0 if success, 1 if no change, 2 if error.
+   */
+  int ConfigDecRate(uint16_t decimationRate);
 
   /**
    * Get the SPI port number.
diff --git a/wpilibc/src/main/native/include/frc/ADIS16470_IMU.h b/wpilibc/src/main/native/include/frc/ADIS16470_IMU.h
index e3b521c..f594c2b 100644
--- a/wpilibc/src/main/native/include/frc/ADIS16470_IMU.h
+++ b/wpilibc/src/main/native/include/frc/ADIS16470_IMU.h
@@ -53,55 +53,109 @@
 class ADIS16470_IMU : public wpi::Sendable,
                       public wpi::SendableHelper<ADIS16470_IMU> {
  public:
-  /* ADIS16470 Calibration Time Enum Class */
+  /**
+   * ADIS16470 calibration times.
+   */
   enum class CalibrationTime {
+    /// 32 ms calibration time.
     _32ms = 0,
+    /// 64 ms calibration time.
     _64ms = 1,
+    /// 128 ms calibration time.
     _128ms = 2,
+    /// 256 ms calibration time.
     _256ms = 3,
+    /// 512 ms calibration time.
     _512ms = 4,
+    /// 1 s calibration time.
     _1s = 5,
+    /// 2 s calibration time.
     _2s = 6,
+    /// 4 s calibration time.
     _4s = 7,
+    /// 8 s calibration time.
     _8s = 8,
+    /// 16 s calibration time.
     _16s = 9,
+    /// 32 s calibration time.
     _32s = 10,
+    /// 64 s calibration time.
     _64s = 11
   };
 
-  enum IMUAxis { kX, kY, kZ };
+  /**
+   * IMU axes.
+   *
+   * kX, kY, and kZ refer to the IMU's X, Y, and Z axes respectively. kYaw,
+   * kPitch, and kRoll are configured by the user to refer to an X, Y, or Z
+   * axis.
+   */
+  enum IMUAxis {
+    /// The IMU's X axis.
+    kX,
+    /// The IMU's Y axis.
+    kY,
+    /// The IMU's Z axis.
+    kZ,
+    /// The user-configured yaw axis.
+    kYaw,
+    /// The user-configured pitch axis.
+    kPitch,
+    /// The user-configured roll axis.
+    kRoll
+  };
 
   /**
-   * @brief Default constructor. Uses CS0 on the 10-pin SPI port, the yaw axis
-   * is set to the IMU Z axis, and calibration time is defaulted to 4 seconds.
+   * Creates a new ADIS16740 IMU object.
+   *
+   * The default setup is the onboard SPI port with a calibration time of 4
+   * seconds. Yaw, pitch, and roll are kZ, kX, and kY respectively.
    */
   ADIS16470_IMU();
 
   /**
-   * @brief Customizable constructor. Allows the SPI port and CS to be
-   * customized, the yaw axis used for GetAngle() is adjustable, and initial
-   * calibration time can be modified.
+   * Creates a new ADIS16740 IMU object.
    *
-   * @param yaw_axis Selects the "default" axis to use for GetAngle() and
-   * GetRate()
+   * The default setup is the onboard SPI port with a calibration time of 4
+   * seconds.
    *
-   * @param port The SPI port and CS where the IMU is connected.
+   * <b><i>Input axes limited to kX, kY and kZ. Specifying kYaw, kPitch,or kRoll
+   * will result in an error.</i></b>
    *
-   * @param cal_time The calibration time that should be used on start-up.
+   * @param yaw_axis The axis that measures the yaw
+   * @param pitch_axis The axis that measures the pitch
+   * @param roll_axis The axis that measures the roll
    */
-  explicit ADIS16470_IMU(IMUAxis yaw_axis, SPI::Port port,
-                         CalibrationTime cal_time);
+  ADIS16470_IMU(IMUAxis yaw_axis, IMUAxis pitch_axis, IMUAxis roll_axis);
 
   /**
-   * @brief Destructor. Kills the acquisition loop and closes the SPI
-   * peripheral.
+   * Creates a new ADIS16740 IMU object.
+   *
+   * <b><i>Input axes limited to kX, kY and kZ. Specifying kYaw, kPitch, or
+   * kRoll will result in an error.</i></b>
+   *
+   * @param yaw_axis The axis that measures the yaw
+   * @param pitch_axis The axis that measures the pitch
+   * @param roll_axis The axis that measures the roll
+   * @param port The SPI Port the gyro is plugged into
+   * @param cal_time Calibration time
    */
+  explicit ADIS16470_IMU(IMUAxis yaw_axis, IMUAxis pitch_axis,
+                         IMUAxis roll_axis, frc::SPI::Port port,
+                         CalibrationTime cal_time);
+
   ~ADIS16470_IMU() override;
 
   ADIS16470_IMU(ADIS16470_IMU&&) = default;
   ADIS16470_IMU& operator=(ADIS16470_IMU&&) = default;
 
-  int ConfigDecRate(uint16_t reg);
+  /**
+   * Configures the decimation rate of the IMU.
+   *
+   * @param decimationRate The new decimation value.
+   * @return 0 if success, 1 if no change, 2 if error.
+   */
+  int ConfigDecRate(uint16_t decimationRate);
 
   /**
    * @brief Switches the active SPI port to standard SPI mode, writes the
@@ -116,22 +170,66 @@
   int ConfigCalTime(CalibrationTime new_cal_time);
 
   /**
-   * @brief Resets (zeros) the xgyro, ygyro, and zgyro angle integrations.
+   * Reset the gyro.
    *
    * Resets the gyro accumulations to a heading of zero. This can be used if
-   * the "zero" orientation of the sensor needs to be changed in runtime.
+   * there is significant drift in the gyro and it needs to be recalibrated
+   * after running.
    */
   void Reset();
 
   /**
-   * Returns the yaw axis angle in degrees (CCW positive).
+   * Allow the designated gyro angle to be set to a given value. This may happen
+   * with unread values in the buffer, it is suggested that the IMU is not
+   * moving when this method is run.
+   *
+   * @param axis IMUAxis that will be changed
+   * @param angle The new angle (CCW positive)
    */
-  units::degree_t GetAngle() const;
+  void SetGyroAngle(IMUAxis axis, units::degree_t angle);
 
   /**
-   * Returns the yaw axis angular rate in degrees per second (CCW positive).
+   * Allow the gyro angle X to be set to a given value. This may happen with
+   * unread values in the buffer, it is suggested that the IMU is not moving
+   * when this method is run.
+   *
+   * @param angle The new angle (CCW positive)
    */
-  units::degrees_per_second_t GetRate() const;
+  void SetGyroAngleX(units::degree_t angle);
+
+  /**
+   * Allow the gyro angle Y to be set to a given value. This may happen with
+   * unread values in the buffer, it is suggested that the IMU is not moving
+   * when this method is run.
+   *
+   * @param angle The new angle (CCW positive)
+   */
+  void SetGyroAngleY(units::degree_t angle);
+
+  /**
+   * Allow the gyro angle Z to be set to a given value. This may happen with
+   * unread values in the buffer, it is suggested that the IMU is not moving
+   * when this method is run.
+   *
+   * @param angle The new angle (CCW positive)
+   */
+  void SetGyroAngleZ(units::degree_t angle);
+
+  /**
+   * Returns the axis angle (CCW positive).
+   *
+   * @param axis The IMUAxis whose angle to return.
+   * @return The axis angle (CCW positive).
+   */
+  units::degree_t GetAngle(IMUAxis axis) const;
+
+  /**
+   * Returns the axis angular rate (CCW positive).
+   *
+   * @param axis The IMUAxis whose rate to return.
+   * @return Axis angular rate (CCW positive).
+   */
+  units::degrees_per_second_t GetRate(IMUAxis axis) const;
 
   /**
    * Returns the acceleration in the X axis.
@@ -148,25 +246,60 @@
    */
   units::meters_per_second_squared_t GetAccelZ() const;
 
+  /**
+   * Returns the X-axis complementary angle.
+   */
   units::degree_t GetXComplementaryAngle() const;
 
+  /**
+   * Returns the Y-axis complementary angle.
+   */
   units::degree_t GetYComplementaryAngle() const;
 
+  /**
+   * Returns the X-axis filtered acceleration angle.
+   */
   units::degree_t GetXFilteredAccelAngle() const;
 
+  /**
+   * Returns the Y-axis filtered acceleration angle.
+   */
   units::degree_t GetYFilteredAccelAngle() const;
 
+  /**
+   * Returns which axis, kX, kY, or kZ, is set to the yaw axis.
+   *
+   * @return IMUAxis Yaw Axis
+   */
   IMUAxis GetYawAxis() const;
 
-  int SetYawAxis(IMUAxis yaw_axis);
-
-  bool IsConnected() const;
-
-  // IMU yaw axis
-  IMUAxis m_yaw_axis;
+  /**
+   * Returns which axis, kX, kY, or kZ, is set to the pitch axis.
+   *
+   * @return IMUAxis Pitch Axis
+   */
+  IMUAxis GetPitchAxis() const;
 
   /**
-   * Get the SPI port number.
+   * Returns which axis, kX, kY, or kZ, is set to the roll axis.
+   *
+   * @return IMUAxis Roll Axis
+   */
+  IMUAxis GetRollAxis() const;
+
+  /**
+   * Checks the connection status of the IMU.
+   *
+   * @return True if the IMU is connected, false otherwise.
+   */
+  bool IsConnected() const;
+
+  IMUAxis m_yaw_axis;
+  IMUAxis m_pitch_axis;
+  IMUAxis m_roll_axis;
+
+  /**
+   * Gets the SPI port number.
    *
    * @return The SPI port number.
    */
@@ -175,7 +308,7 @@
   void InitSendable(wpi::SendableBuilder& builder) override;
 
  private:
-  /* ADIS16470 Register Map Declaration */
+  // Register Map Declaration
   static constexpr uint8_t FLASH_CNT = 0x00;  // Flash memory write count
   static constexpr uint8_t DIAG_STAT =
       0x02;  // Diagnostic and operational status
@@ -276,25 +409,15 @@
   static constexpr uint8_t FLSHCNT_HIGH =
       0x7E;  // Flash update count, upper word
 
-  /* ADIS16470 Auto SPI Data Packets */
-  static constexpr uint8_t m_autospi_x_packet[16] = {
-      X_DELTANG_OUT, FLASH_CNT, X_DELTANG_LOW, FLASH_CNT, X_GYRO_OUT, FLASH_CNT,
-      Y_GYRO_OUT,    FLASH_CNT, Z_GYRO_OUT,    FLASH_CNT, X_ACCL_OUT, FLASH_CNT,
-      Y_ACCL_OUT,    FLASH_CNT, Z_ACCL_OUT,    FLASH_CNT};
+  // Auto SPI Data Packet to read all thrre gyro axes.
+  static constexpr uint8_t m_autospi_allangle_packet[24] = {
+      X_DELTANG_OUT, FLASH_CNT,     X_DELTANG_LOW, FLASH_CNT,     Y_DELTANG_OUT,
+      FLASH_CNT,     Y_DELTANG_LOW, FLASH_CNT,     Z_DELTANG_OUT, FLASH_CNT,
+      Z_DELTANG_LOW, FLASH_CNT,     X_GYRO_OUT,    FLASH_CNT,     Y_GYRO_OUT,
+      FLASH_CNT,     Z_GYRO_OUT,    FLASH_CNT,     X_ACCL_OUT,    FLASH_CNT,
+      Y_ACCL_OUT,    FLASH_CNT,     Z_ACCL_OUT,    FLASH_CNT};
 
-  static constexpr uint8_t m_autospi_y_packet[16] = {
-      Y_DELTANG_OUT, FLASH_CNT, Y_DELTANG_LOW, FLASH_CNT, X_GYRO_OUT, FLASH_CNT,
-      Y_GYRO_OUT,    FLASH_CNT, Z_GYRO_OUT,    FLASH_CNT, X_ACCL_OUT, FLASH_CNT,
-      Y_ACCL_OUT,    FLASH_CNT, Z_ACCL_OUT,    FLASH_CNT};
-
-  static constexpr uint8_t m_autospi_z_packet[16] = {
-      Z_DELTANG_OUT, FLASH_CNT, Z_DELTANG_LOW, FLASH_CNT, X_GYRO_OUT, FLASH_CNT,
-      Y_GYRO_OUT,    FLASH_CNT, Z_GYRO_OUT,    FLASH_CNT, X_ACCL_OUT, FLASH_CNT,
-      Y_ACCL_OUT,    FLASH_CNT, Z_ACCL_OUT,    FLASH_CNT};
-
-  /* ADIS16470 Constants */
-  static constexpr double delta_angle_sf =
-      2160.0 / 2147483648.0; /* 2160 / (2^31) */
+  static constexpr double delta_angle_sf = 2160.0 / 2147483648.0;
   static constexpr double rad_to_deg = 57.2957795;
   static constexpr double deg_to_rad = 0.0174532;
   static constexpr double grav = 9.81;
@@ -350,8 +473,10 @@
 
   void Close();
 
-  // Integrated gyro value
-  double m_integ_angle = 0.0;
+  // Integrated gyro angles.
+  double m_integ_angle_x = 0.0;
+  double m_integ_angle_y = 0.0;
+  double m_integ_angle_z = 0.0;
 
   // Instant raw outputs
   double m_gyro_rate_x = 0.0;
diff --git a/wpilibc/src/main/native/include/frc/ADXL345_I2C.h b/wpilibc/src/main/native/include/frc/ADXL345_I2C.h
index 2fe0da4..4c6d9df 100644
--- a/wpilibc/src/main/native/include/frc/ADXL345_I2C.h
+++ b/wpilibc/src/main/native/include/frc/ADXL345_I2C.h
@@ -26,17 +26,48 @@
 class ADXL345_I2C : public nt::NTSendable,
                     public wpi::SendableHelper<ADXL345_I2C> {
  public:
-  enum Range { kRange_2G = 0, kRange_4G = 1, kRange_8G = 2, kRange_16G = 3 };
-
-  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
-
-  struct AllAxes {
-    double XAxis;
-    double YAxis;
-    double ZAxis;
+  /**
+   * Accelerometer range.
+   */
+  enum Range {
+    /// 2 Gs max.
+    kRange_2G = 0,
+    /// 4 Gs max.
+    kRange_4G = 1,
+    /// 8 Gs max.
+    kRange_8G = 2,
+    /// 16 Gs max.
+    kRange_16G = 3
   };
 
   /**
+   * Accelerometer axes.
+   */
+  enum Axes {
+    /// X axis.
+    kAxis_X = 0x00,
+    /// Y axis.
+    kAxis_Y = 0x02,
+    /// Z axis.
+    kAxis_Z = 0x04
+  };
+
+  /**
+   * Container type for accelerations from all axes.
+   */
+  struct AllAxes {
+    /// Acceleration along the X axis in g-forces.
+    double XAxis = 0.0;
+    /// Acceleration along the Y axis in g-forces.
+    double YAxis = 0.0;
+    /// Acceleration along the Z axis in g-forces.
+    double ZAxis = 0.0;
+  };
+
+  /// Default I2C device address.
+  static constexpr int kAddress = 0x1D;
+
+  /**
    * Constructs the ADXL345 Accelerometer over I2C.
    *
    * @param port          The I2C port the accelerometer is attached to
@@ -100,7 +131,7 @@
 
   void InitSendable(nt::NTSendableBuilder& builder) override;
 
- protected:
+ private:
   I2C m_i2c;
 
   hal::SimDevice m_simDevice;
@@ -109,7 +140,6 @@
   hal::SimDouble m_simY;
   hal::SimDouble m_simZ;
 
-  static constexpr int kAddress = 0x1D;
   static constexpr int kPowerCtlRegister = 0x2D;
   static constexpr int kDataFormatRegister = 0x31;
   static constexpr int kDataRegister = 0x32;
diff --git a/wpilibc/src/main/native/include/frc/ADXL345_SPI.h b/wpilibc/src/main/native/include/frc/ADXL345_SPI.h
index 3f2d8ae..305be92 100644
--- a/wpilibc/src/main/native/include/frc/ADXL345_SPI.h
+++ b/wpilibc/src/main/native/include/frc/ADXL345_SPI.h
@@ -21,14 +21,42 @@
 class ADXL345_SPI : public nt::NTSendable,
                     public wpi::SendableHelper<ADXL345_SPI> {
  public:
-  enum Range { kRange_2G = 0, kRange_4G = 1, kRange_8G = 2, kRange_16G = 3 };
+  /**
+   * Accelerometer range.
+   */
+  enum Range {
+    /// 2 Gs max.
+    kRange_2G = 0,
+    /// 4 Gs max.
+    kRange_4G = 1,
+    /// 8 Gs max.
+    kRange_8G = 2,
+    /// 16 Gs max.
+    kRange_16G = 3
+  };
 
-  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
+  /**
+   * Accelerometer axes.
+   */
+  enum Axes {
+    /// X axis.
+    kAxis_X = 0x00,
+    /// Y axis.
+    kAxis_Y = 0x02,
+    /// Z axis.
+    kAxis_Z = 0x04
+  };
 
+  /**
+   * Container type for accelerations from all axes.
+   */
   struct AllAxes {
-    double XAxis;
-    double YAxis;
-    double ZAxis;
+    /// Acceleration along the X axis in g-forces.
+    double XAxis = 0.0;
+    /// Acceleration along the Y axis in g-forces.
+    double YAxis = 0.0;
+    /// Acceleration along the Z axis in g-forces.
+    double ZAxis = 0.0;
   };
 
   /**
@@ -93,7 +121,7 @@
 
   void InitSendable(nt::NTSendableBuilder& builder) override;
 
- protected:
+ private:
   SPI m_spi;
 
   hal::SimDevice m_simDevice;
diff --git a/wpilibc/src/main/native/include/frc/ADXL362.h b/wpilibc/src/main/native/include/frc/ADXL362.h
index ddf6ebe..0332b31 100644
--- a/wpilibc/src/main/native/include/frc/ADXL362.h
+++ b/wpilibc/src/main/native/include/frc/ADXL362.h
@@ -19,13 +19,40 @@
  */
 class ADXL362 : public nt::NTSendable, public wpi::SendableHelper<ADXL362> {
  public:
-  enum Range { kRange_2G = 0, kRange_4G = 1, kRange_8G = 2 };
+  /**
+   * Accelerometer range.
+   */
+  enum Range {
+    /// 2 Gs max.
+    kRange_2G = 0,
+    /// 4 Gs max.
+    kRange_4G = 1,
+    /// 8 Gs max.
+    kRange_8G = 2
+  };
 
-  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
+  /**
+   * Accelerometer axes.
+   */
+  enum Axes {
+    /// X axis.
+    kAxis_X = 0x00,
+    /// Y axis.
+    kAxis_Y = 0x02,
+    /// Z axis.
+    kAxis_Z = 0x04
+  };
+
+  /**
+   * Container type for accelerations from all axes.
+   */
   struct AllAxes {
-    double XAxis;
-    double YAxis;
-    double ZAxis;
+    /// Acceleration along the X axis in g-forces.
+    double XAxis = 0.0;
+    /// Acceleration along the Y axis in g-forces.
+    double YAxis = 0.0;
+    /// Acceleration along the Z axis in g-forces.
+    double ZAxis = 0.0;
   };
 
  public:
diff --git a/wpilibc/src/main/native/include/frc/AddressableLED.h b/wpilibc/src/main/native/include/frc/AddressableLED.h
index 198eb67..26738bb 100644
--- a/wpilibc/src/main/native/include/frc/AddressableLED.h
+++ b/wpilibc/src/main/native/include/frc/AddressableLED.h
@@ -22,7 +22,9 @@
  * By default, the timing supports WS2812B LEDs, but is configurable using
  * SetBitTiming()
  *
- * <p>Only 1 LED driver is currently supported by the roboRIO.
+ * <p>Only 1 LED driver is currently supported by the roboRIO. However,
+ * multiple LED strips can be connected in series and controlled from the
+ * single driver.
  */
 class AddressableLED {
  public:
diff --git a/wpilibc/src/main/native/include/frc/AnalogGyro.h b/wpilibc/src/main/native/include/frc/AnalogGyro.h
index 0c472fb..3913b40 100644
--- a/wpilibc/src/main/native/include/frc/AnalogGyro.h
+++ b/wpilibc/src/main/native/include/frc/AnalogGyro.h
@@ -218,10 +218,8 @@
 
   void InitSendable(wpi::SendableBuilder& builder) override;
 
- protected:
-  std::shared_ptr<AnalogInput> m_analog;
-
  private:
+  std::shared_ptr<AnalogInput> m_analog;
   hal::Handle<HAL_GyroHandle> m_gyroHandle;
 };
 
diff --git a/wpilibc/src/main/native/include/frc/AnalogOutput.h b/wpilibc/src/main/native/include/frc/AnalogOutput.h
index ccb3c9c..4151ae6 100644
--- a/wpilibc/src/main/native/include/frc/AnalogOutput.h
+++ b/wpilibc/src/main/native/include/frc/AnalogOutput.h
@@ -33,14 +33,14 @@
   /**
    * Set the value of the analog output.
    *
-   * @param voltage The output value in Volts, from 0.0 to +5.0
+   * @param voltage The output value in Volts, from 0.0 to +5.0.
    */
   void SetVoltage(double voltage);
 
   /**
-   * Get the voltage of the analog output
+   * Get the voltage of the analog output.
    *
-   * @return The value in Volts, from 0.0 to +5.0
+   * @return The value in Volts, from 0.0 to +5.0.
    */
   double GetVoltage() const;
 
diff --git a/wpilibc/src/main/native/include/frc/AnalogTriggerType.h b/wpilibc/src/main/native/include/frc/AnalogTriggerType.h
index c706c34..0db114d 100644
--- a/wpilibc/src/main/native/include/frc/AnalogTriggerType.h
+++ b/wpilibc/src/main/native/include/frc/AnalogTriggerType.h
@@ -6,10 +6,15 @@
 
 namespace frc {
 
+/** Defines the state in which the AnalogTrigger triggers. */
 enum class AnalogTriggerType {
+  /// In window.
   kInWindow = 0,
+  /// State.
   kState = 1,
+  /// Rising Pulse.
   kRisingPulse = 2,
+  /// Falling pulse.
   kFallingPulse = 3
 };
 
diff --git a/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h b/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h
index a8f0adc..270ed80 100644
--- a/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h
+++ b/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h
@@ -17,7 +17,17 @@
 class BuiltInAccelerometer : public wpi::Sendable,
                              public wpi::SendableHelper<BuiltInAccelerometer> {
  public:
-  enum Range { kRange_2G = 0, kRange_4G = 1, kRange_8G = 2 };
+  /**
+   * Accelerometer range.
+   */
+  enum Range {
+    /// 2 Gs max.
+    kRange_2G = 0,
+    /// 4 Gs max.
+    kRange_4G = 1,
+    /// 8 Gs max.
+    kRange_8G = 2
+  };
 
   /**
    * Constructor.
diff --git a/wpilibc/src/main/native/include/frc/CAN.h b/wpilibc/src/main/native/include/frc/CAN.h
index dc04988..1f5d168 100644
--- a/wpilibc/src/main/native/include/frc/CAN.h
+++ b/wpilibc/src/main/native/include/frc/CAN.h
@@ -170,7 +170,10 @@
    */
   static uint64_t GetTimestampBaseTime();
 
+  /// Team manufacturer.
   static constexpr HAL_CANManufacturer kTeamManufacturer = HAL_CAN_Man_kTeamUse;
+
+  /// Team device type.
   static constexpr HAL_CANDeviceType kTeamDeviceType =
       HAL_CAN_Dev_kMiscellaneous;
 
diff --git a/wpilibc/src/main/native/include/frc/CompressorConfigType.h b/wpilibc/src/main/native/include/frc/CompressorConfigType.h
index 5a5a1c1..b933804 100644
--- a/wpilibc/src/main/native/include/frc/CompressorConfigType.h
+++ b/wpilibc/src/main/native/include/frc/CompressorConfigType.h
@@ -5,10 +5,17 @@
 #pragma once
 
 namespace frc {
+/**
+ * Compressor config type.
+ */
 enum class CompressorConfigType {
+  /// Disabled.
   Disabled = 0,
+  /// Digital.
   Digital = 1,
+  /// Analog.
   Analog = 2,
+  /// Hybrid.
   Hybrid = 3
 };
 
diff --git a/wpilibc/src/main/native/include/frc/Counter.h b/wpilibc/src/main/native/include/frc/Counter.h
index 71eebca..3720dde 100644
--- a/wpilibc/src/main/native/include/frc/Counter.h
+++ b/wpilibc/src/main/native/include/frc/Counter.h
@@ -451,17 +451,20 @@
   void InitSendable(wpi::SendableBuilder& builder) override;
 
  protected:
-  // Makes the counter count up.
+  /// Makes the counter count up.
   std::shared_ptr<DigitalSource> m_upSource;
 
-  // Makes the counter count down.
+  /// Makes the counter count down.
   std::shared_ptr<DigitalSource> m_downSource;
 
-  // The FPGA counter object
+  /// The FPGA counter object
   hal::Handle<HAL_CounterHandle> m_counter;
 
  private:
-  int m_index = 0;  // The index of this counter.
+  /// The index of this counter.
+  int m_index = 0;
+
+  /// Distance of travel for each tick.
   double m_distancePerPulse = 1;
 
   friend class DigitalGlitchFilter;
diff --git a/wpilibc/src/main/native/include/frc/DMA.h b/wpilibc/src/main/native/include/frc/DMA.h
index 1bbf268..d09368f 100644
--- a/wpilibc/src/main/native/include/frc/DMA.h
+++ b/wpilibc/src/main/native/include/frc/DMA.h
@@ -17,6 +17,9 @@
 class PWM;
 class PWMMotorController;
 
+/**
+ * Class for configuring Direct Memory Access (DMA) of FPGA inputs.
+ */
 class DMA {
   friend class DMASample;
 
@@ -27,32 +30,162 @@
   DMA& operator=(DMA&& other) = default;
   DMA(DMA&& other) = default;
 
+  /**
+   * Sets whether DMA is paused.
+   *
+   * @param pause True pauses DMA.
+   */
   void SetPause(bool pause);
-  void SetTimedTrigger(units::second_t seconds);
+
+  /**
+   * Sets DMA to trigger at an interval.
+   *
+   * @param period Period at which to trigger DMA.
+   */
+  void SetTimedTrigger(units::second_t period);
+
+  /**
+   * Sets number of DMA cycles to trigger.
+   *
+   * @param cycles Number of cycles.
+   */
   void SetTimedTriggerCycles(int cycles);
 
+  /**
+   * Adds position data for an encoder to be collected by DMA.
+   *
+   * This can only be called if DMA is not started.
+   *
+   * @param encoder Encoder to add to DMA.
+   */
   void AddEncoder(const Encoder* encoder);
+
+  /**
+   * Adds timer data for an encoder to be collected by DMA.
+   *
+   * This can only be called if DMA is not started.
+   *
+   * @param encoder Encoder to add to DMA.
+   */
   void AddEncoderPeriod(const Encoder* encoder);
 
+  /**
+   * Adds position data for an counter to be collected by DMA.
+   *
+   * This can only be called if DMA is not started.
+   *
+   * @param counter Counter to add to DMA.
+   */
   void AddCounter(const Counter* counter);
+
+  /**
+   * Adds timer data for an counter to be collected by DMA.
+   *
+   * This can only be called if DMA is not started.
+   *
+   * @param counter Counter to add to DMA.
+   */
   void AddCounterPeriod(const Counter* counter);
 
+  /**
+   * Adds a digital source to be collected by DMA.
+   *
+   * This can only be called if DMA is not started.
+   *
+   * @param digitalSource DigitalSource to add to DMA.
+   */
   void AddDigitalSource(const DigitalSource* digitalSource);
 
+  /**
+   * Adds a digital source to be collected by DMA.
+   *
+   * This can only be called if DMA is not started.
+   *
+   * @param digitalSource DigitalSource to add to DMA.
+   */
   void AddDutyCycle(const DutyCycle* digitalSource);
 
+  /**
+   * Adds an analog input to be collected by DMA.
+   *
+   * This can only be called if DMA is not started.
+   *
+   * @param analogInput AnalogInput to add to DMA.
+   */
   void AddAnalogInput(const AnalogInput* analogInput);
+
+  /**
+   * Adds averaged data of an analog input to be collected by DMA.
+   *
+   * This can only be called if DMA is not started.
+   *
+   * @param analogInput AnalogInput to add to DMA.
+   */
   void AddAveragedAnalogInput(const AnalogInput* analogInput);
+
+  /**
+   * Adds accumulator data of an analog input to be collected by DMA.
+   *
+   * This can only be called if DMA is not started.
+   *
+   * @param analogInput AnalogInput to add to DMA.
+   */
   void AddAnalogAccumulator(const AnalogInput* analogInput);
 
+  /**
+   * Sets an external DMA trigger.
+   *
+   * @param source the source to trigger from.
+   * @param rising trigger on rising edge.
+   * @param falling trigger on falling edge.
+   * @return the index of the trigger
+   */
   int SetExternalTrigger(DigitalSource* source, bool rising, bool falling);
+
+  /**
+   * Sets a DMA PWM edge trigger.
+   *
+   * @param pwm the PWM to trigger from.
+   * @param rising trigger on rising edge.
+   * @param falling trigger on falling edge.
+   * @return the index of the trigger
+   */
   int SetPwmEdgeTrigger(PWM* pwm, bool rising, bool falling);
+
+  /**
+   * Sets a DMA PWMMotorController edge trigger.
+   *
+   * @param pwm the PWMMotorController to trigger from.
+   * @param rising trigger on rising edge.
+   * @param falling trigger on falling edge.
+   * @return the index of the trigger
+   */
   int SetPwmEdgeTrigger(PWMMotorController* pwm, bool rising, bool falling);
 
+  /**
+   * Clear all sensors from the DMA collection list.
+   *
+   * This can only be called if DMA is not started.
+   */
   void ClearSensors();
+
+  /**
+   * Clear all external triggers from the DMA trigger list.
+   *
+   * This can only be called if DMA is not started.
+   */
   void ClearExternalTriggers();
 
+  /**
+   * Starts DMA Collection.
+   *
+   * @param queueDepth The number of objects to be able to queue.
+   */
   void Start(int queueDepth);
+
+  /**
+   * Stops DMA Collection.
+   */
   void Stop();
 
  private:
diff --git a/wpilibc/src/main/native/include/frc/DMASample.h b/wpilibc/src/main/native/include/frc/DMASample.h
index 48a0a9e..b2bed41 100644
--- a/wpilibc/src/main/native/include/frc/DMASample.h
+++ b/wpilibc/src/main/native/include/frc/DMASample.h
@@ -17,30 +17,71 @@
 #include "frc/Encoder.h"
 
 namespace frc {
+/**
+ * DMA sample.
+ */
 class DMASample : public HAL_DMASample {
  public:
+  /**
+   * DMA read status.
+   */
   enum class DMAReadStatus {
+    /// OK status.
     kOk = HAL_DMA_OK,
+    /// Timeout status.
     kTimeout = HAL_DMA_TIMEOUT,
+    /// Error status.
     kError = HAL_DMA_ERROR
   };
 
+  /**
+   * Retrieves a new DMA sample.
+   *
+   * @param dma DMA object.
+   * @param timeout Timeout for retrieval.
+   * @param remaining Number of remaining samples.
+   * @param status DMA read status.
+   */
   DMAReadStatus Update(const DMA* dma, units::second_t timeout,
                        int32_t* remaining, int32_t* status) {
     return static_cast<DMAReadStatus>(
         HAL_ReadDMA(dma->dmaHandle, this, timeout.value(), remaining, status));
   }
 
+  /**
+   * Returns the DMA sample time in microseconds.
+   *
+   * @return The DMA sample time in microseconds.
+   */
   uint64_t GetTime() const { return timeStamp; }
 
+  /**
+   * Returns the DMA sample timestamp.
+   *
+   * @return The DMA sample timestamp.
+   */
   units::second_t GetTimeStamp() const {
     return units::second_t{static_cast<double>(GetTime()) * 1.0e-6};
   }
 
+  /**
+   * Returns raw encoder value from DMA.
+   *
+   * @param encoder Encoder used for DMA.
+   * @param status DMA read status.
+   * @return Raw encoder value from DMA.
+   */
   int32_t GetEncoderRaw(const Encoder* encoder, int32_t* status) const {
     return HAL_GetDMASampleEncoderRaw(this, encoder->m_encoder, status);
   }
 
+  /**
+   * Returns encoder distance from DMA.
+   *
+   * @param encoder Encoder used for DMA.
+   * @param status DMA read status.
+   * @return Encoder distance from DMA.
+   */
   double GetEncoderDistance(const Encoder* encoder, int32_t* status) const {
     double val = GetEncoderRaw(encoder, status);
     val *= encoder->DecodingScaleFactor();
@@ -48,41 +89,97 @@
     return val;
   }
 
+  /**
+   * Returns raw encoder period from DMA.
+   *
+   * @param encoder Encoder used for DMA.
+   * @param status DMA read status.
+   * @return Raw encoder period from DMA.
+   */
   int32_t GetEncoderPeriodRaw(const Encoder* encoder, int32_t* status) const {
     return HAL_GetDMASampleEncoderPeriodRaw(this, encoder->m_encoder, status);
   }
 
+  /**
+   * Returns counter value from DMA.
+   *
+   * @param counter Counter used for DMA.
+   * @param status DMA read status.
+   * @return Counter value from DMA.
+   */
   int32_t GetCounter(const Counter* counter, int32_t* status) const {
     return HAL_GetDMASampleCounter(this, counter->m_counter, status);
   }
 
+  /**
+   * Returns counter period from DMA.
+   *
+   * @param counter Counter used for DMA.
+   * @param status DMA read status.
+   * @return Counter period from DMA.
+   */
   int32_t GetCounterPeriod(const Counter* counter, int32_t* status) const {
     return HAL_GetDMASampleCounterPeriod(this, counter->m_counter, status);
   }
 
+  /**
+   * Returns digital source value from DMA.
+   *
+   * @param digitalSource DigitalSource used for DMA.
+   * @param status DMA read status.
+   * @return DigitalSource value from DMA.
+   */
   bool GetDigitalSource(const DigitalSource* digitalSource,
                         int32_t* status) const {
     return HAL_GetDMASampleDigitalSource(
         this, digitalSource->GetPortHandleForRouting(), status);
   }
 
+  /**
+   * Returns raw analog input value from DMA.
+   *
+   * @param analogInput AnalogInput used for DMA.
+   * @param status DMA read status.
+   * @return Raw analog input value from DMA.
+   */
   int32_t GetAnalogInputRaw(const AnalogInput* analogInput,
                             int32_t* status) const {
     return HAL_GetDMASampleAnalogInputRaw(this, analogInput->m_port, status);
   }
 
+  /**
+   * Returns analog input voltage from DMA.
+   *
+   * @param analogInput AnalogInput used for DMA.
+   * @param status DMA read status.
+   * @return Analog input voltage from DMA.
+   */
   double GetAnalogInputVoltage(const AnalogInput* analogInput,
                                int32_t* status) {
     return HAL_GetAnalogValueToVolts(
         analogInput->m_port, GetAnalogInputRaw(analogInput, status), status);
   }
 
+  /**
+   * Returns averaged analog input raw value from DMA.
+   *
+   * @param analogInput AnalogInput used for DMA.
+   * @param status DMA read status.
+   * @return Averaged analog input raw value from DMA.
+   */
   int32_t GetAveragedAnalogInputRaw(const AnalogInput* analogInput,
                                     int32_t* status) const {
     return HAL_GetDMASampleAveragedAnalogInputRaw(this, analogInput->m_port,
                                                   status);
   }
 
+  /**
+   * Returns averaged analog input voltage from DMA.
+   *
+   * @param analogInput AnalogInput used for DMA.
+   * @param status DMA read status.
+   * @return Averaged analog input voltage from DMA.
+   */
   double GetAveragedAnalogInputVoltage(const AnalogInput* analogInput,
                                        int32_t* status) {
     return HAL_GetAnalogValueToVolts(
@@ -90,18 +187,40 @@
         status);
   }
 
+  /**
+   * Returns analog accumulator value from DMA.
+   *
+   * @param analogInput AnalogInput used for DMA.
+   * @param count Accumulator sample count.
+   * @param value Accumulator value.
+   * @param status DMA read status.
+   */
   void GetAnalogAccumulator(const AnalogInput* analogInput, int64_t* count,
                             int64_t* value, int32_t* status) const {
     return HAL_GetDMASampleAnalogAccumulator(this, analogInput->m_port, count,
                                              value, status);
   }
 
+  /**
+   * Returns raw duty cycle output from DMA.
+   *
+   * @param dutyCycle DutyCycle used for DMA.
+   * @param status DMA read status.
+   * @return Raw duty cycle output from DMA.
+   */
   int32_t GetDutyCycleOutputRaw(const DutyCycle* dutyCycle,
                                 int32_t* status) const {
     return HAL_GetDMASampleDutyCycleOutputRaw(this, dutyCycle->m_handle,
                                               status);
   }
 
+  /**
+   * Returns duty cycle output (0-1) from DMA.
+   *
+   * @param dutyCycle DutyCycle used for DMA.
+   * @param status DMA read status.
+   * @return Duty cycle output (0-1) from DMA.
+   */
   double GetDutyCycleOutput(const DutyCycle* dutyCycle, int32_t* status) {
     return GetDutyCycleOutputRaw(dutyCycle, status) /
            static_cast<double>(dutyCycle->GetOutputScaleFactor());
diff --git a/wpilibc/src/main/native/include/frc/DataLogManager.h b/wpilibc/src/main/native/include/frc/DataLogManager.h
index 336af4a..f171cd3 100644
--- a/wpilibc/src/main/native/include/frc/DataLogManager.h
+++ b/wpilibc/src/main/native/include/frc/DataLogManager.h
@@ -17,8 +17,8 @@
  * Centralized data log that provides automatic data log file management. It
  * automatically cleans up old files when disk space is low and renames the file
  * based either on current date/time or (if available) competition match number.
- * The deta file will be saved to a USB flash drive if one is attached, or to
- * /home/lvuser otherwise.
+ * The data file will be saved to a USB flash drive in a folder named "logs" if
+ * one is attached, or to /home/lvuser/logs otherwise.
  *
  * Log files are initially named "FRC_TBD_{random}.wpilog" until the DS
  * connects. After the DS connects, the log file is renamed to
diff --git a/wpilibc/src/main/native/include/frc/DoubleSolenoid.h b/wpilibc/src/main/native/include/frc/DoubleSolenoid.h
index f02ba5a..57c2c11 100644
--- a/wpilibc/src/main/native/include/frc/DoubleSolenoid.h
+++ b/wpilibc/src/main/native/include/frc/DoubleSolenoid.h
@@ -25,7 +25,17 @@
 class DoubleSolenoid : public wpi::Sendable,
                        public wpi::SendableHelper<DoubleSolenoid> {
  public:
-  enum Value { kOff, kForward, kReverse };
+  /**
+   * Possible values for a DoubleSolenoid.
+   */
+  enum Value {
+    /// Off position.
+    kOff,
+    /// Forward position.
+    kForward,
+    /// Reverse position.
+    kReverse
+  };
 
   /**
    * Constructs a double solenoid for a specified module of a specific module
diff --git a/wpilibc/src/main/native/include/frc/DriverStation.h b/wpilibc/src/main/native/include/frc/DriverStation.h
index ea568a7..b9b683f 100644
--- a/wpilibc/src/main/native/include/frc/DriverStation.h
+++ b/wpilibc/src/main/native/include/frc/DriverStation.h
@@ -22,9 +22,31 @@
  */
 class DriverStation final {
  public:
-  enum Alliance { kRed, kBlue };
-  enum MatchType { kNone, kPractice, kQualification, kElimination };
+  /**
+   * The robot alliance that the robot is a part of.
+   */
+  enum Alliance {
+    /// Red alliance.
+    kRed,
+    /// Blue alliance.
+    kBlue
+  };
 
+  /**
+   * The type of robot match that the robot is part of.
+   */
+  enum MatchType {
+    /// None.
+    kNone,
+    /// Practice.
+    kPractice,
+    /// Qualification.
+    kQualification,
+    /// Elimination.
+    kElimination
+  };
+
+  /// Number of Joystick ports.
   static constexpr int kJoystickPorts = 6;
 
   /**
@@ -274,14 +296,13 @@
   static int GetReplayNumber();
 
   /**
-   * Return the alliance that the driver station says it is on from the FMS.
+   * Get the current alliance from the FMS.
    *
    * If the FMS is not connected, it is set from the team alliance setting on
    * the driver station.
    *
-   * This could return kRed or kBlue.
-   *
-   * @return The Alliance enum (kRed, kBlue or kInvalid)
+   * @return The alliance (red or blue) or an empty optional if the alliance is
+   * invalid
    */
   static std::optional<Alliance> GetAlliance();
 
@@ -334,9 +355,25 @@
    */
   static double GetBatteryVoltage();
 
+  /**
+   * Copy data from the DS task for the user. If no new data exists, it will
+   * just be returned, otherwise the data will be copied from the DS polling
+   * loop.
+   */
   static void RefreshData();
 
+  /**
+   * Registers the given handle for DS data refresh notifications.
+   *
+   * @param handle The event handle.
+   */
   static void ProvideRefreshedDataEventHandle(WPI_EventHandle handle);
+
+  /**
+   * Unregisters the given handle from DS data refresh notifications.
+   *
+   * @param handle The event handle.
+   */
   static void RemoveRefreshedDataEventHandle(WPI_EventHandle handle);
 
   /**
diff --git a/wpilibc/src/main/native/include/frc/Encoder.h b/wpilibc/src/main/native/include/frc/Encoder.h
index 7315e16..8d6c10a 100644
--- a/wpilibc/src/main/native/include/frc/Encoder.h
+++ b/wpilibc/src/main/native/include/frc/Encoder.h
@@ -42,10 +42,17 @@
   friend class DMASample;
 
  public:
+  /**
+   * Encoder indexing types.
+   */
   enum IndexingType {
+    /// Reset while the signal is high.
     kResetWhileHigh,
+    /// Reset while the signal is low.
     kResetWhileLow,
+    /// Reset on falling edge of the signal.
     kResetOnFallingEdge,
+    /// Reset on rising edge of the signal.
     kResetOnRisingEdge
   };
 
diff --git a/wpilibc/src/main/native/include/frc/GenericHID.h b/wpilibc/src/main/native/include/frc/GenericHID.h
index f6db94c..aac4bec 100644
--- a/wpilibc/src/main/native/include/frc/GenericHID.h
+++ b/wpilibc/src/main/native/include/frc/GenericHID.h
@@ -23,25 +23,55 @@
  */
 class GenericHID {
  public:
-  enum RumbleType { kLeftRumble, kRightRumble, kBothRumble };
+  /**
+   * Represents a rumble output on the Joystick.
+   */
+  enum RumbleType {
+    /// Left rumble motor.
+    kLeftRumble,
+    /// Right rumble motor.
+    kRightRumble,
+    /// Both left and right rumble motors.
+    kBothRumble
+  };
 
+  /**
+   * USB HID interface type.
+   */
   enum HIDType {
+    /// Unknown.
     kUnknown = -1,
+    /// XInputUnknown.
     kXInputUnknown = 0,
+    /// XInputGamepad.
     kXInputGamepad = 1,
+    /// XInputWheel.
     kXInputWheel = 2,
+    /// XInputArcadeStick.
     kXInputArcadeStick = 3,
+    /// XInputFlightStick.
     kXInputFlightStick = 4,
+    /// XInputDancePad.
     kXInputDancePad = 5,
+    /// XInputGuitar.
     kXInputGuitar = 6,
+    /// XInputGuitar2.
     kXInputGuitar2 = 7,
+    /// XInputDrumKit.
     kXInputDrumKit = 8,
+    /// XInputGuitar3.
     kXInputGuitar3 = 11,
+    /// XInputArcadePad.
     kXInputArcadePad = 19,
+    /// HIDJoystick.
     kHIDJoystick = 20,
+    /// HIDGamepad.
     kHIDGamepad = 21,
+    /// HIDDriving.
     kHIDDriving = 22,
+    /// HIDFlight.
     kHIDFlight = 23,
+    /// HID1stPerson.
     kHID1stPerson = 24
   };
 
diff --git a/wpilibc/src/main/native/include/frc/I2C.h b/wpilibc/src/main/native/include/frc/I2C.h
index 9489fcf..07f3d4a 100644
--- a/wpilibc/src/main/native/include/frc/I2C.h
+++ b/wpilibc/src/main/native/include/frc/I2C.h
@@ -22,7 +22,15 @@
  */
 class I2C {
  public:
-  enum Port { kOnboard = 0, kMXP };
+  /**
+   * I2C connection ports.
+   */
+  enum Port {
+    /// Onboard I2C port.
+    kOnboard = 0,
+    /// MXP (roboRIO MXP) I2C port.
+    kMXP
+  };
 
   /**
    * Constructor.
@@ -37,7 +45,18 @@
   I2C(I2C&&) = default;
   I2C& operator=(I2C&&) = default;
 
+  /**
+   * Returns I2C port.
+   *
+   * @return I2C port.
+   */
   Port GetPort() const;
+
+  /**
+   * Returns I2C device address.
+   *
+   * @return I2C device address.
+   */
   int GetDeviceAddress() const;
 
   /**
diff --git a/wpilibc/src/main/native/include/frc/IterativeRobotBase.h b/wpilibc/src/main/native/include/frc/IterativeRobotBase.h
index 42b0c71..be7687d 100644
--- a/wpilibc/src/main/native/include/frc/IterativeRobotBase.h
+++ b/wpilibc/src/main/native/include/frc/IterativeRobotBase.h
@@ -215,7 +215,7 @@
   /**
    * Sets whether LiveWindow operation is enabled during test mode.
    *
-   * @param testLW True to enable, false to disable. Defaults to true.
+   * @param testLW True to enable, false to disable. Defaults to false.
    * @throws if called in test mode.
    */
   void EnableLiveWindowInTest(bool testLW);
@@ -243,6 +243,9 @@
   IterativeRobotBase(IterativeRobotBase&&) = default;
   IterativeRobotBase& operator=(IterativeRobotBase&&) = default;
 
+  /**
+   * Loop function.
+   */
   void LoopFunc();
 
  private:
@@ -252,7 +255,7 @@
   units::second_t m_period;
   Watchdog m_watchdog;
   bool m_ntFlushEnabled = true;
-  bool m_lwEnabledInTest = true;
+  bool m_lwEnabledInTest = false;
   bool m_calledDsConnected = false;
 
   void PrintLoopOverrunMessage();
diff --git a/wpilibc/src/main/native/include/frc/Joystick.h b/wpilibc/src/main/native/include/frc/Joystick.h
index a955718..d9c4144 100644
--- a/wpilibc/src/main/native/include/frc/Joystick.h
+++ b/wpilibc/src/main/native/include/frc/Joystick.h
@@ -22,14 +22,42 @@
  */
 class Joystick : public GenericHID {
  public:
+  /// Default X axis channel.
   static constexpr int kDefaultXChannel = 0;
+  /// Default Y axis channel.
   static constexpr int kDefaultYChannel = 1;
+  /// Default Z axis channel.
   static constexpr int kDefaultZChannel = 2;
+  /// Default twist axis channel.
   static constexpr int kDefaultTwistChannel = 2;
+  /// Default throttle axis channel.
   static constexpr int kDefaultThrottleChannel = 3;
 
-  enum AxisType { kXAxis, kYAxis, kZAxis, kTwistAxis, kThrottleAxis };
-  enum ButtonType { kTriggerButton, kTopButton };
+  /**
+   * Represents an analog axis on a joystick.
+   */
+  enum AxisType {
+    /// X axis.
+    kXAxis,
+    /// Y axis.
+    kYAxis,
+    /// Z axis.
+    kZAxis,
+    /// Twist axis.
+    kTwistAxis,
+    /// Throttle axis.
+    kThrottleAxis
+  };
+
+  /**
+   * Represents a digital button on a joystick.
+   */
+  enum ButtonType {
+    /// kTrigger.
+    kTriggerButton,
+    /// kTop.
+    kTopButton
+  };
 
   /**
    * Construct an instance of a joystick.
diff --git a/wpilibc/src/main/native/include/frc/MotorSafety.h b/wpilibc/src/main/native/include/frc/MotorSafety.h
index a17cdc0..efe7806 100644
--- a/wpilibc/src/main/native/include/frc/MotorSafety.h
+++ b/wpilibc/src/main/native/include/frc/MotorSafety.h
@@ -93,12 +93,15 @@
    */
   static void CheckMotors();
 
+  /**
+   * Called to stop the motor when the timeout expires.
+   */
   virtual void StopMotor() = 0;
 
   /**
-   * The return value from this method is printed out when an error occurs
+   * Returns a description to print when an error occurs.
    *
-   * This method must not throw!
+   * @return Description to print when an error occurs.
    */
   virtual std::string GetDescription() const = 0;
 
diff --git a/wpilibc/src/main/native/include/frc/PS4Controller.h b/wpilibc/src/main/native/include/frc/PS4Controller.h
index 9487634..881f856 100644
--- a/wpilibc/src/main/native/include/frc/PS4Controller.h
+++ b/wpilibc/src/main/native/include/frc/PS4Controller.h
@@ -11,10 +11,14 @@
 /**
  * Handle input from PS4 controllers connected to the Driver Station.
  *
- * <p>This class handles PS4 input that comes from the Driver Station. Each time
+ * This class handles PS4 input that comes from the Driver Station. Each time
  * a value is requested the most recent value is returned. There is a single
  * class instance for each controller and the mapping of ports to hardware
  * buttons depends on the code in the Driver Station.
+ *
+ * Only first party controllers from Sony are guaranteed to have the correct
+ * mapping, and only through the official NI DS. Sim is not guaranteed to have
+ * the same mapping, as well as any 3rd party controllers.
  */
 class PS4Controller : public GenericHID {
  public:
@@ -499,29 +503,55 @@
    */
   BooleanEvent Touchpad(EventLoop* loop) const;
 
+  /**
+   * Represents a digital button on a PS4Controller.
+   */
   struct Button {
+    /// Square button.
     static constexpr int kSquare = 1;
+    /// X button.
     static constexpr int kCross = 2;
+    /// Circle button.
     static constexpr int kCircle = 3;
+    /// Triangle button.
     static constexpr int kTriangle = 4;
+    /// Left Trigger 1 button.
     static constexpr int kL1 = 5;
+    /// Right Trigger 1 button.
     static constexpr int kR1 = 6;
+    /// Left Trigger 2 button.
     static constexpr int kL2 = 7;
+    /// Right Trigger 2 button.
     static constexpr int kR2 = 8;
+    /// Share button.
     static constexpr int kShare = 9;
+    /// Option button.
     static constexpr int kOptions = 10;
+    /// Left stick button.
     static constexpr int kL3 = 11;
+    /// Right stick button.
     static constexpr int kR3 = 12;
+    /// PlayStation button.
     static constexpr int kPS = 13;
+    /// Touchpad click button.
     static constexpr int kTouchpad = 14;
   };
 
+  /**
+   * Represents an axis on a PS4Controller.
+   */
   struct Axis {
+    /// Left X axis.
     static constexpr int kLeftX = 0;
+    /// Left Y axis.
     static constexpr int kLeftY = 1;
+    /// Right X axis.
     static constexpr int kRightX = 2;
+    /// Right Y axis.
     static constexpr int kRightY = 5;
+    /// Left Trigger 2.
     static constexpr int kL2 = 3;
+    /// Right Trigger 2.
     static constexpr int kR2 = 4;
   };
 };
diff --git a/wpilibc/src/main/native/include/frc/PS5Controller.h b/wpilibc/src/main/native/include/frc/PS5Controller.h
index 2a24f5e..e9d5235 100644
--- a/wpilibc/src/main/native/include/frc/PS5Controller.h
+++ b/wpilibc/src/main/native/include/frc/PS5Controller.h
@@ -11,10 +11,14 @@
 /**
  * Handle input from PS5 controllers connected to the Driver Station.
  *
- * <p>This class handles PS5 input that comes from the Driver Station. Each time
+ * This class handles PS5 input that comes from the Driver Station. Each time
  * a value is requested the most recent value is returned. There is a single
  * class instance for each controller and the mapping of ports to hardware
  * buttons depends on the code in the Driver Station.
+ *
+ * Only first party controllers from Sony are guaranteed to have the correct
+ * mapping, and only through the official NI DS. Sim is not guaranteed to have
+ * the same mapping, as well as any 3rd party controllers.
  */
 class PS5Controller : public GenericHID {
  public:
@@ -499,30 +503,56 @@
    */
   BooleanEvent Touchpad(EventLoop* loop) const;
 
+  /**
+   * Represents a digital button on a PS5Controller.
+   */
   struct Button {
-    static constexpr int kSquare = 3;
-    static constexpr int kCross = 1;
-    static constexpr int kCircle = 2;
+    /// Square button.
+    static constexpr int kSquare = 1;
+    /// X button.
+    static constexpr int kCross = 2;
+    /// Circle button.
+    static constexpr int kCircle = 3;
+    /// Triangle button.
     static constexpr int kTriangle = 4;
+    /// Left trigger 1 button.
     static constexpr int kL1 = 5;
+    /// Right trigger 1 button.
     static constexpr int kR1 = 6;
+    /// Left trigger 2 button.
     static constexpr int kL2 = 7;
+    /// Right trigger 2 button.
     static constexpr int kR2 = 8;
+    /// Create button.
     static constexpr int kCreate = 9;
+    /// Options button.
     static constexpr int kOptions = 10;
-    static constexpr int kL3 = 12;
-    static constexpr int kR3 = 13;
-    static constexpr int kPS = 11;
+    /// Left stick button.
+    static constexpr int kL3 = 11;
+    /// Right stick button.
+    static constexpr int kR3 = 12;
+    /// PlayStation button.
+    static constexpr int kPS = 13;
+    /// Touchpad click button.
     static constexpr int kTouchpad = 14;
   };
 
+  /**
+   * Represents an axis on a PS5Controller.
+   */
   struct Axis {
+    /// Left X axis.
     static constexpr int kLeftX = 0;
+    /// Left Y axis.
     static constexpr int kLeftY = 1;
-    static constexpr int kRightX = 3;
-    static constexpr int kRightY = 4;
-    static constexpr int kL2 = 2;
-    static constexpr int kR2 = 5;
+    /// Right X axis.
+    static constexpr int kRightX = 2;
+    /// Right Y axis.
+    static constexpr int kRightY = 5;
+    /// Left Trigger 2.
+    static constexpr int kL2 = 3;
+    /// Right Trigger 2.
+    static constexpr int kR2 = 4;
   };
 };
 
diff --git a/wpilibc/src/main/native/include/frc/PWM.h b/wpilibc/src/main/native/include/frc/PWM.h
index 0871c9c..c1f162e 100644
--- a/wpilibc/src/main/native/include/frc/PWM.h
+++ b/wpilibc/src/main/native/include/frc/PWM.h
@@ -144,6 +144,9 @@
    */
   void SetPeriodMultiplier(PeriodMultiplier mult);
 
+  /**
+   * Latches PWM to zero.
+   */
   void SetZeroLatch();
 
   /**
diff --git a/wpilibc/src/main/native/include/frc/PneumaticHub.h b/wpilibc/src/main/native/include/frc/PneumaticHub.h
index b69b3d5..790a9d0 100644
--- a/wpilibc/src/main/native/include/frc/PneumaticHub.h
+++ b/wpilibc/src/main/native/include/frc/PneumaticHub.h
@@ -7,6 +7,7 @@
 #include <memory>
 
 #include <hal/Types.h>
+#include <units/pressure.h>
 #include <wpi/DenseMap.h>
 #include <wpi/mutex.h>
 
@@ -157,6 +158,15 @@
     uint32_t Brownout : 1;
     uint32_t CanWarning : 1;
     uint32_t HardwareFault : 1;
+
+    /**
+     * Gets whether there is a fault at the specified channel.
+     * @param channel Channel to check for faults.
+     * @return True if a a fault exists at the channel, otherwise false.
+     * @throws A ChannelIndexOutOfRange error if the provided channel is outside
+     * of the range supported by the hardware.
+     */
+    bool GetChannelFault(int channel) const;
   };
 
   /**
diff --git a/wpilibc/src/main/native/include/frc/PneumaticsBase.h b/wpilibc/src/main/native/include/frc/PneumaticsBase.h
index 59f899f..52ae9b0 100644
--- a/wpilibc/src/main/native/include/frc/PneumaticsBase.h
+++ b/wpilibc/src/main/native/include/frc/PneumaticsBase.h
@@ -18,6 +18,10 @@
 class Solenoid;
 class DoubleSolenoid;
 class Compressor;
+
+/**
+ * Base class for pneumatics devices.
+ */
 class PneumaticsBase {
  public:
   virtual ~PneumaticsBase() = default;
diff --git a/wpilibc/src/main/native/include/frc/PneumaticsModuleType.h b/wpilibc/src/main/native/include/frc/PneumaticsModuleType.h
index 7f70662..4fb225a 100644
--- a/wpilibc/src/main/native/include/frc/PneumaticsModuleType.h
+++ b/wpilibc/src/main/native/include/frc/PneumaticsModuleType.h
@@ -5,5 +5,13 @@
 #pragma once
 
 namespace frc {
-enum class PneumaticsModuleType { CTREPCM, REVPH };
+/**
+ * Pneumatics module type.
+ */
+enum class PneumaticsModuleType {
+  /// CTRE PCM.
+  CTREPCM,
+  /// REV PH.
+  REVPH
+};
 }  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/PowerDistribution.h b/wpilibc/src/main/native/include/frc/PowerDistribution.h
index 763e6bf..4a6eb4f 100644
--- a/wpilibc/src/main/native/include/frc/PowerDistribution.h
+++ b/wpilibc/src/main/native/include/frc/PowerDistribution.h
@@ -17,8 +17,18 @@
 class PowerDistribution : public wpi::Sendable,
                           public wpi::SendableHelper<PowerDistribution> {
  public:
+  /// Default module number.
   static constexpr int kDefaultModule = -1;
-  enum class ModuleType { kCTRE = 1, kRev = 2 };
+
+  /**
+   * Power distribution module type.
+   */
+  enum class ModuleType {
+    /// CTRE (Cross The Road Electronics) CTRE Power Distribution Panel (PDP).
+    kCTRE = 1,
+    /// REV Power Distribution Hub (PDH).
+    kRev = 2
+  };
 
   /**
    * Constructs a PowerDistribution object.
@@ -159,8 +169,22 @@
     uint32_t Brownout : 1;
     uint32_t CanWarning : 1;
     uint32_t HardwareFault : 1;
+
+    /**
+     * Gets whether there is a breaker fault at a specified channel.
+     * @param channel Channel to check for faults.
+     * @return If there is a breaker fault.
+     * @throws A ChannelIndexOutOfRange error if the given int is outside of the
+     * range supported by the hardware.
+     */
+    bool GetBreakerFault(int channel) const;
   };
 
+  /**
+   * Returns the power distribution faults.
+   *
+   * @return The power distribution faults.
+   */
   Faults GetFaults() const;
 
   struct StickyFaults {
@@ -192,8 +216,23 @@
     uint32_t CanWarning : 1;
     uint32_t CanBusOff : 1;
     uint32_t HasReset : 1;
+
+    /**
+     * Gets whether there is a sticky breaker fault at the specified channel.
+     * @param channel Index to check for sticky faults.
+     * @return True if there is a sticky breaker fault at the channel, otherwise
+     * false.
+     * @throws A ChannelIndexOutOfRange error if the provided channel is outside
+     * of the range supported by the hardware.
+     */
+    bool GetBreakerFault(int channel) const;
   };
 
+  /**
+   * Returns the power distribution sticky faults.
+   *
+   * @return The power distribution sticky faults.
+   */
   StickyFaults GetStickyFaults() const;
 
   void InitSendable(wpi::SendableBuilder& builder) override;
diff --git a/wpilibc/src/main/native/include/frc/Relay.h b/wpilibc/src/main/native/include/frc/Relay.h
index 4765c64..d08a000 100644
--- a/wpilibc/src/main/native/include/frc/Relay.h
+++ b/wpilibc/src/main/native/include/frc/Relay.h
@@ -31,8 +31,31 @@
               public wpi::Sendable,
               public wpi::SendableHelper<Relay> {
  public:
-  enum Value { kOff, kOn, kForward, kReverse };
-  enum Direction { kBothDirections, kForwardOnly, kReverseOnly };
+  /**
+   * The state to drive a Relay to.
+   */
+  enum Value {
+    /// Off.
+    kOff,
+    /// On.
+    kOn,
+    /// Forward.
+    kForward,
+    /// Reverse.
+    kReverse
+  };
+
+  /**
+   * The Direction(s) that a relay is configured to operate in.
+   */
+  enum Direction {
+    /// Both directions are valid.
+    kBothDirections,
+    /// Only forward is valid.
+    kForwardOnly,
+    /// Only reverse is valid.
+    kReverseOnly
+  };
 
   /**
    * Relay constructor given a channel.
diff --git a/wpilibc/src/main/native/include/frc/RobotBase.h b/wpilibc/src/main/native/include/frc/RobotBase.h
index 504ac81..6dff369 100644
--- a/wpilibc/src/main/native/include/frc/RobotBase.h
+++ b/wpilibc/src/main/native/include/frc/RobotBase.h
@@ -189,7 +189,9 @@
   bool IsTestEnabled() const;
 
   /**
-   * Gets the ID of the main robot thread.
+   * Returns the main thread ID.
+   *
+   * @return The main thread ID.
    */
   static std::thread::id GetThreadId();
 
diff --git a/wpilibc/src/main/native/include/frc/RobotController.h b/wpilibc/src/main/native/include/frc/RobotController.h
index bf65a8c..5d8ddfb 100644
--- a/wpilibc/src/main/native/include/frc/RobotController.h
+++ b/wpilibc/src/main/native/include/frc/RobotController.h
@@ -21,6 +21,8 @@
   int transmitErrorCount;
 };
 
+enum RadioLEDState { kOff = 0, kGreen = 1, kRed = 2, kOrange = 3 };
+
 class RobotController {
  public:
   RobotController() = delete;
@@ -81,6 +83,10 @@
   /**
    * Get 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.
+   *
    * @return True if the button is currently pressed down
    */
   static bool GetUserButton();
@@ -275,6 +281,23 @@
   static units::celsius_t GetCPUTemp();
 
   /**
+   * Set the state of the "Radio" LED. On the RoboRIO, this writes to sysfs, so
+   * this function should not be called multiple times per loop cycle to avoid
+   * overruns.
+   * @param state The state to set the LED to.
+   */
+  static void SetRadioLEDState(RadioLEDState state);
+
+  /**
+   * Get the state of the "Radio" LED. On the RoboRIO, this reads from sysfs, so
+   * this function should not be called multiple times per loop cycle to avoid
+   * overruns.
+   *
+   * @return The state of the LED.
+   */
+  static RadioLEDState GetRadioLEDState();
+
+  /**
    * Get the current status of the CAN bus.
    *
    * @return The status of the CAN bus
diff --git a/wpilibc/src/main/native/include/frc/RobotState.h b/wpilibc/src/main/native/include/frc/RobotState.h
index 0489b9b..ec8700e 100644
--- a/wpilibc/src/main/native/include/frc/RobotState.h
+++ b/wpilibc/src/main/native/include/frc/RobotState.h
@@ -6,15 +6,53 @@
 
 namespace frc {
 
+/**
+ * Robot state utility functions.
+ */
 class RobotState {
  public:
   RobotState() = delete;
 
+  /**
+   * Returns true if the robot is disabled.
+   *
+   * @return True if the robot is disabled.
+   */
   static bool IsDisabled();
+
+  /**
+   * Returns true if the robot is enabled.
+   *
+   * @return True if the robot is enabled.
+   */
   static bool IsEnabled();
+
+  /**
+   * Returns true if the robot is E-stopped.
+   *
+   * @return True if the robot is E-stopped.
+   */
   static bool IsEStopped();
+
+  /**
+   * Returns true if the robot is in teleop mode.
+   *
+   * @return True if the robot is in teleop mode.
+   */
   static bool IsTeleop();
+
+  /**
+   * Returns true if the robot is in autonomous mode.
+   *
+   * @return True if the robot is in autonomous mode.
+   */
   static bool IsAutonomous();
+
+  /**
+   * Returns true if the robot is in test mode.
+   *
+   * @return True if the robot is in test mode.
+   */
   static bool IsTest();
 };
 
diff --git a/wpilibc/src/main/native/include/frc/RuntimeType.h b/wpilibc/src/main/native/include/frc/RuntimeType.h
index c3a8a0b..2be444a 100644
--- a/wpilibc/src/main/native/include/frc/RuntimeType.h
+++ b/wpilibc/src/main/native/include/frc/RuntimeType.h
@@ -5,5 +5,15 @@
 #pragma once
 
 namespace frc {
-enum RuntimeType { kRoboRIO, kRoboRIO2, kSimulation };
+/**
+ * Runtime type.
+ */
+enum RuntimeType {
+  /// roboRIO 1.0.
+  kRoboRIO,
+  /// roboRIO 2.0.
+  kRoboRIO2,
+  /// Simulation runtime.
+  kSimulation
+};
 }  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/SPI.h b/wpilibc/src/main/native/include/frc/SPI.h
index 1158cbd..5b170ba 100644
--- a/wpilibc/src/main/native/include/frc/SPI.h
+++ b/wpilibc/src/main/native/include/frc/SPI.h
@@ -25,14 +25,34 @@
  */
 class SPI {
  public:
-  enum Port { kOnboardCS0 = 0, kOnboardCS1, kOnboardCS2, kOnboardCS3, kMXP };
+  /**
+   * SPI port.
+   */
+  enum Port {
+    /// Onboard SPI bus port CS0.
+    kOnboardCS0 = 0,
+    /// Onboard SPI bus port CS1.
+    kOnboardCS1,
+    /// Onboard SPI bus port CS2.
+    kOnboardCS2,
+    /// Onboard SPI bus port CS3.
+    kOnboardCS3,
+    /// MXP (roboRIO MXP) SPI bus port.
+    kMXP
+  };
+
+  /**
+   * SPI mode.
+   */
   enum Mode {
-    kMode0 = HAL_SPI_kMode0, /*!< Clock idle low, data sampled on rising edge */
-    kMode1 =
-        HAL_SPI_kMode1, /*!< Clock idle low, data sampled on falling edge */
-    kMode2 =
-        HAL_SPI_kMode2, /*!< Clock idle high, data sampled on falling edge */
-    kMode3 = HAL_SPI_kMode3 /*!< Clock idle high, data sampled on rising edge */
+    /// Clock idle low, data sampled on rising edge.
+    kMode0 = HAL_SPI_kMode0,
+    /// Clock idle low, data sampled on falling edge.
+    kMode1 = HAL_SPI_kMode1,
+    /// Clock idle high, data sampled on falling edge.
+    kMode2 = HAL_SPI_kMode2,
+    /// Clock idle high, data sampled on rising edge.
+    kMode3 = HAL_SPI_kMode3
   };
 
   /**
@@ -47,6 +67,11 @@
   SPI(SPI&&) = default;
   SPI& operator=(SPI&&) = default;
 
+  /**
+   * Returns the SPI port.
+   *
+   * @return The SPI port.
+   */
   Port GetPort() const;
 
   /**
diff --git a/wpilibc/src/main/native/include/frc/SerialPort.h b/wpilibc/src/main/native/include/frc/SerialPort.h
index dcc0a2e..b7784da 100644
--- a/wpilibc/src/main/native/include/frc/SerialPort.h
+++ b/wpilibc/src/main/native/include/frc/SerialPort.h
@@ -26,30 +26,73 @@
  */
 class SerialPort {
  public:
+  /**
+   * Serial port.
+   */
+  enum Port {
+    /// Onboard serial port on the roboRIO.
+    kOnboard = 0,
+    /// MXP (roboRIO MXP) serial port.
+    kMXP = 1,
+    /// USB serial port (same as KUSB1).
+    kUSB = 2,
+    /// USB serial port 1.
+    kUSB1 = 2,
+    /// USB serial port 2.
+    kUSB2 = 3
+  };
+
+  /**
+   * Represents the parity to use for serial communications.
+   */
   enum Parity {
+    /// No parity.
     kParity_None = 0,
+    /// Odd parity.
     kParity_Odd = 1,
+    /// Even parity.
     kParity_Even = 2,
+    /// Parity bit always on.
     kParity_Mark = 3,
+    /// Parity bit always off.
     kParity_Space = 4
   };
 
+  /**
+   * Represents the number of stop bits to use for Serial Communication.
+   */
   enum StopBits {
+    /// One stop bit.
     kStopBits_One = 10,
+    /// One and a half stop bits.
     kStopBits_OnePointFive = 15,
+    /// Two stop bits.
     kStopBits_Two = 20
   };
 
+  /**
+   * Represents what type of flow control to use for serial communication.
+   */
   enum FlowControl {
+    /// No flow control.
     kFlowControl_None = 0,
+    /// XON/XOFF flow control.
     kFlowControl_XonXoff = 1,
+    /// RTS/CTS flow control.
     kFlowControl_RtsCts = 2,
+    /// DTS/DSR flow control.
     kFlowControl_DtrDsr = 4
   };
 
-  enum WriteBufferMode { kFlushOnAccess = 1, kFlushWhenFull = 2 };
-
-  enum Port { kOnboard = 0, kMXP = 1, kUSB = 2, kUSB1 = 2, kUSB2 = 3 };
+  /**
+   * Represents which type of buffer mode to use when writing to a serial port.
+   */
+  enum WriteBufferMode {
+    /// Flush the buffer on each access.
+    kFlushOnAccess = 1,
+    /// Flush the buffer when it is full.
+    kFlushWhenFull = 2
+  };
 
   /**
    * Create an instance of a Serial Port class.
diff --git a/wpilibc/src/main/native/include/frc/Servo.h b/wpilibc/src/main/native/include/frc/Servo.h
index 9383641..76b39a0 100644
--- a/wpilibc/src/main/native/include/frc/Servo.h
+++ b/wpilibc/src/main/native/include/frc/Servo.h
@@ -19,6 +19,11 @@
 class Servo : public PWM {
  public:
   /**
+   * Constructor.
+   *
+   * By default, 2.4 ms is used as the max PWM value and 0.6 ms is used as the
+   * min PWM value.
+   *
    * @param channel The PWM channel to which the servo is attached. 0-9 are
    *                on-board, 10-19 are on the MXP port
    */
diff --git a/wpilibc/src/main/native/include/frc/StadiaController.h b/wpilibc/src/main/native/include/frc/StadiaController.h
new file mode 100644
index 0000000..cc9dbae
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/StadiaController.h
@@ -0,0 +1,568 @@
+// 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 "frc/GenericHID.h"
+
+namespace frc {
+
+/**
+ * Handle input from Stadia controllers connected to the Driver
+ * Station.
+ *
+ * This class handles Stadia input that comes from the Driver Station. Each time
+ * a value is requested the most recent value is returned. There is a single
+ * class instance for each controller and the mapping of ports to hardware
+ * buttons depends on the code in the Driver Station.
+ */
+class StadiaController : public GenericHID {
+ public:
+  /**
+   * Construct an instance of a Stadia controller.
+   *
+   * The controller index is the USB port on the Driver Station.
+   *
+   * @param port The port on the Driver Station that the controller is plugged
+   *             into (0-5).
+   */
+  explicit StadiaController(int port);
+
+  ~StadiaController() override = default;
+
+  StadiaController(StadiaController&&) = default;
+  StadiaController& operator=(StadiaController&&) = default;
+
+  /**
+   * Get the X axis value of left side of the controller.
+   *
+   * @return the axis value
+   */
+  double GetLeftX() const;
+
+  /**
+   * Get the X axis value of right side of the controller.
+   *
+   * @return the axis value
+   */
+  double GetRightX() const;
+
+  /**
+   * Get the Y axis value of left side of the controller.
+   *
+   * @return the axis value
+   */
+  double GetLeftY() const;
+
+  /**
+   * Get the Y axis value of right side of the controller.
+   *
+   * @return the axis value
+   */
+  double GetRightY() const;
+
+  /**
+   * Read the value of the left bumper (LB) button on the controller.
+   *
+   * @return the state of the button
+   */
+  bool GetLeftBumper() const;
+
+  /**
+   * Read the value of the right bumper (RB) button on the controller.
+   *
+   * @return the state of the button
+   */
+  bool GetRightBumper() const;
+
+  /**
+   * Whether the left bumper (LB) was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check
+   */
+  bool GetLeftBumperPressed();
+
+  /**
+   * Whether the right bumper (RB) was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check
+   */
+  bool GetRightBumperPressed();
+
+  /**
+   * Whether the left bumper (LB) was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetLeftBumperReleased();
+
+  /**
+   * Whether the right bumper (RB) was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetRightBumperReleased();
+
+  /**
+   * Constructs an event instance around the left bumper's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the left bumper's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent LeftBumper(EventLoop* loop) const;
+
+  /**
+   * Constructs an event instance around the right bumper's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the right bumper's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent RightBumper(EventLoop* loop) const;
+
+  /**
+   * Read the value of the left stick button (LSB) on the controller.
+   *
+   * @return the state of the button
+   */
+  bool GetLeftStickButton() const;
+
+  /**
+   * Read the value of the right stick button (RSB) on the controller.
+   *
+   * @return the state of the button
+   */
+  bool GetRightStickButton() const;
+
+  /**
+   * Whether the left stick button (LSB) was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetLeftStickButtonPressed();
+
+  /**
+   * Whether the right stick button (RSB) was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check
+   */
+  bool GetRightStickButtonPressed();
+
+  /**
+   * Whether the left stick button (LSB) was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetLeftStickButtonReleased();
+
+  /**
+   * Whether the right stick button (RSB) was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetRightStickButtonReleased();
+
+  /**
+   * Constructs an event instance around the left stick's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the left stick's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent LeftStick(EventLoop* loop) const;
+
+  /**
+   * Constructs an event instance around the right stick's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the right stick's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent RightStick(EventLoop* loop) const;
+
+  /**
+   * Read the value of the A button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetAButton() const;
+
+  /**
+   * Whether the A button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetAButtonPressed();
+
+  /**
+   * Whether the A button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetAButtonReleased();
+
+  /**
+   * Constructs an event instance around the A button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the A button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent A(EventLoop* loop) const;
+
+  /**
+   * Read the value of the B button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetBButton() const;
+
+  /**
+   * Whether the B button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetBButtonPressed();
+
+  /**
+   * Whether the B button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetBButtonReleased();
+
+  /**
+   * Constructs an event instance around the B button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the B button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent B(EventLoop* loop) const;
+
+  /**
+   * Read the value of the X button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetXButton() const;
+
+  /**
+   * Whether the X button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetXButtonPressed();
+
+  /**
+   * Whether the X button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetXButtonReleased();
+
+  /**
+   * Constructs an event instance around the X button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the X button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent X(EventLoop* loop) const;
+
+  /**
+   * Read the value of the Y button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetYButton() const;
+
+  /**
+   * Whether the Y button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetYButtonPressed();
+
+  /**
+   * Whether the Y button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetYButtonReleased();
+
+  /**
+   * Constructs an event instance around the Y button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the Y button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Y(EventLoop* loop) const;
+
+  /**
+   * Read the value of the ellipses button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetEllipsesButton() const;
+
+  /**
+   * Whether the ellipses button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetEllipsesButtonPressed();
+
+  /**
+   * Whether the ellipses button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetEllipsesButtonReleased();
+
+  /**
+   * Constructs an event instance around the ellipses button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the ellipses button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Ellipses(EventLoop* loop) const;
+
+  /**
+   * Read the value of the hamburger button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetHamburgerButton() const;
+
+  /**
+   * Whether the hamburger button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetHamburgerButtonPressed();
+
+  /**
+   * Whether the hamburger button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetHamburgerButtonReleased();
+
+  /**
+   * Constructs an event instance around the hamburger button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the hamburger button's digital
+   * signal attached to the given loop.
+   */
+  BooleanEvent Hamburger(EventLoop* loop) const;
+
+  /**
+   * Read the value of the stadia button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetStadiaButton() const;
+
+  /**
+   * Whether the stadia button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetStadiaButtonPressed();
+
+  /**
+   * Whether the stadia button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetStadiaButtonReleased();
+
+  /**
+   * Constructs an event instance around the stadia button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the stadia button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Stadia(EventLoop* loop) const;
+
+  /**
+   * Read the value of the google button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetGoogleButton() const;
+
+  /**
+   * Whether the google button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetGoogleButtonPressed();
+
+  /**
+   * Whether the google button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetGoogleButtonReleased();
+
+  /**
+   * Constructs an event instance around the google button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the google button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Google(EventLoop* loop) const;
+
+  /**
+   * Read the value of the frame button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetFrameButton() const;
+
+  /**
+   * Whether the frame button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetFrameButtonPressed();
+
+  /**
+   * Whether the frame button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetFrameButtonReleased();
+
+  /**
+   * Constructs an event instance around the frame button's digital signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the frame button's digital signal
+   * attached to the given loop.
+   */
+  BooleanEvent Frame(EventLoop* loop) const;
+
+  /**
+   * Read the value of the left trigger button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetLeftTriggerButton() const;
+
+  /**
+   * Whether the left trigger button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetLeftTriggerButtonPressed();
+
+  /**
+   * Whether the left trigger button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetLeftTriggerButtonReleased();
+
+  /**
+   * Constructs an event instance around the left trigger button's digital
+   * signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the left trigger button's digital
+   * signal attached to the given loop.
+   */
+  BooleanEvent LeftTrigger(EventLoop* loop) const;
+
+  /**
+   * Read the value of the right trigger button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetRightTriggerButton() const;
+
+  /**
+   * Whether the right trigger button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetRightTriggerButtonPressed();
+
+  /**
+   * Whether the right trigger button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetRightTriggerButtonReleased();
+
+  /**
+   * Constructs an event instance around the right trigger button's digital
+   * signal.
+   *
+   * @param loop the event loop instance to attach the event to.
+   * @return an event instance representing the right trigger button's digital
+   * signal attached to the given loop.
+   */
+  BooleanEvent RightTrigger(EventLoop* loop) const;
+
+  /**
+   * Represents a digital button on a StadiaController.
+   */
+  struct Button {
+    /// A button.
+    static constexpr int kA = 1;
+    /// B button.
+    static constexpr int kB = 2;
+    /// X button.
+    static constexpr int kX = 3;
+    /// Y button.
+    static constexpr int kY = 4;
+    /// Left bumper button.
+    static constexpr int kLeftBumper = 5;
+    /// Right bumper button.
+    static constexpr int kRightBumper = 6;
+    /// Left stick button.
+    static constexpr int kLeftStick = 7;
+    /// Right stick button.
+    static constexpr int kRightStick = 8;
+    /// Ellipses button.
+    static constexpr int kEllipses = 9;
+    /// Hamburger button.
+    static constexpr int kHamburger = 10;
+    /// Stadia button.
+    static constexpr int kStadia = 11;
+    /// Right trigger button.
+    static constexpr int kRightTrigger = 12;
+    /// Left trigger button.
+    static constexpr int kLeftTrigger = 13;
+    /// Google button.
+    static constexpr int kGoogle = 14;
+    /// Frame button.
+    static constexpr int kFrame = 15;
+  };
+
+  /**
+   * Represents an axis on a StadiaController.
+   */
+  struct Axis {
+    /// Left X axis.
+    static constexpr int kLeftX = 0;
+    /// Right X axis.
+    static constexpr int kRightX = 4;
+    /// Left Y axis.
+    static constexpr int kLeftY = 1;
+    /// Right Y axis.
+    static constexpr int kRightY = 5;
+  };
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/SynchronousInterrupt.h b/wpilibc/src/main/native/include/frc/SynchronousInterrupt.h
index fbe0fca..3e396e8 100644
--- a/wpilibc/src/main/native/include/frc/SynchronousInterrupt.h
+++ b/wpilibc/src/main/native/include/frc/SynchronousInterrupt.h
@@ -25,9 +25,13 @@
    * Event trigger combinations for a synchronous interrupt.
    */
   enum WaitResult {
+    /// Timeout event.
     kTimeout = 0x0,
+    /// Rising edge event.
     kRisingEdge = 0x1,
+    /// Falling edge event.
     kFallingEdge = 0x100,
+    /// Both rising and falling edge events.
     kBoth = 0x101,
   };
 
diff --git a/wpilibc/src/main/native/include/frc/TimedRobot.h b/wpilibc/src/main/native/include/frc/TimedRobot.h
index f32e748..dcc510a 100644
--- a/wpilibc/src/main/native/include/frc/TimedRobot.h
+++ b/wpilibc/src/main/native/include/frc/TimedRobot.h
@@ -29,6 +29,7 @@
  */
 class TimedRobot : public IterativeRobotBase {
  public:
+  /// Default loop period.
   static constexpr auto kDefaultPeriod = 20_ms;
 
   /**
diff --git a/wpilibc/src/main/native/include/frc/Ultrasonic.h b/wpilibc/src/main/native/include/frc/Ultrasonic.h
index 137a5b7..f06392c 100644
--- a/wpilibc/src/main/native/include/frc/Ultrasonic.h
+++ b/wpilibc/src/main/native/include/frc/Ultrasonic.h
@@ -90,6 +90,11 @@
   Ultrasonic(Ultrasonic&&) = default;
   Ultrasonic& operator=(Ultrasonic&&) = default;
 
+  /**
+   * Returns the echo channel.
+   *
+   * @return The echo channel.
+   */
   int GetEchoChannel() const;
 
   /**
diff --git a/wpilibc/src/main/native/include/frc/XboxController.h b/wpilibc/src/main/native/include/frc/XboxController.h
index 3caba1a..4b720c1 100644
--- a/wpilibc/src/main/native/include/frc/XboxController.h
+++ b/wpilibc/src/main/native/include/frc/XboxController.h
@@ -16,6 +16,10 @@
  * value is requested the most recent value is returned. There is a single class
  * instance for each controller and the mapping of ports to hardware buttons
  * depends on the code in the Driver Station.
+ *
+ * Only first party controllers from Microsoft are guaranteed to have the
+ * correct mapping, and only through the official NI DS. Sim is not guaranteed
+ * to have the same mapping, as well as any 3rd party controllers.
  */
 class XboxController : public GenericHID {
  public:
@@ -422,25 +426,43 @@
    */
   BooleanEvent RightTrigger(EventLoop* loop) const;
 
+  /** Represents a digital button on an XboxController. */
   struct Button {
+    /// Left bumper.
     static constexpr int kLeftBumper = 5;
+    /// Right bumper.
     static constexpr int kRightBumper = 6;
+    /// Left stick.
     static constexpr int kLeftStick = 9;
+    /// Right stick.
     static constexpr int kRightStick = 10;
+    /// A.
     static constexpr int kA = 1;
+    /// B.
     static constexpr int kB = 2;
+    /// X.
     static constexpr int kX = 3;
+    /// Y.
     static constexpr int kY = 4;
+    /// Back.
     static constexpr int kBack = 7;
+    /// Start.
     static constexpr int kStart = 8;
   };
 
+  /** Represents an axis on an XboxController. */
   struct Axis {
+    /// Left X.
     static constexpr int kLeftX = 0;
+    /// Right X.
     static constexpr int kRightX = 4;
+    /// Left Y.
     static constexpr int kLeftY = 1;
+    /// Right Y.
     static constexpr int kRightY = 5;
+    /// Left trigger.
     static constexpr int kLeftTrigger = 2;
+    /// Right trigger.
     static constexpr int kRightTrigger = 3;
   };
 };
diff --git a/wpilibc/src/main/native/include/frc/counter/EdgeConfiguration.h b/wpilibc/src/main/native/include/frc/counter/EdgeConfiguration.h
index 508117d..4f5a039 100644
--- a/wpilibc/src/main/native/include/frc/counter/EdgeConfiguration.h
+++ b/wpilibc/src/main/native/include/frc/counter/EdgeConfiguration.h
@@ -5,10 +5,17 @@
 #pragma once
 
 namespace frc {
+/**
+ * Edge configuration.
+ */
 enum class EdgeConfiguration {
+  /// No edge configuration (neither rising nor falling).
   kNone = 0,
+  /// Rising edge configuration.
   kRisingEdge = 0x1,
+  /// Falling edge configuration.
   kFallingEdge = 0x2,
+  /// Both rising and falling edges configuration.
   kBoth = 0x3
 };
 }  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h
index 2e701a3..ccda644 100644
--- a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h
+++ b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h
@@ -4,8 +4,10 @@
 
 #pragma once
 
+#include <functional>
 #include <string>
 
+#include <wpi/deprecated.h>
 #include <wpi/sendable/Sendable.h>
 #include <wpi/sendable/SendableHelper.h>
 
@@ -20,43 +22,9 @@
  * the Kit of Parts drive base, "tank drive", or West Coast Drive.
  *
  * These drive bases typically have drop-center / skid-steer with two or more
- * wheels per side (e.g., 6WD or 8WD). This class takes a MotorController per
- * side. For four and six motor drivetrains, construct and pass in
- * MotorControllerGroup instances as follows.
- *
- * Four motor drivetrain:
- * @code{.cpp}
- * class Robot {
- *  public:
- *   frc::PWMVictorSPX m_frontLeft{1};
- *   frc::PWMVictorSPX m_rearLeft{2};
- *   frc::MotorControllerGroup m_left{m_frontLeft, m_rearLeft};
- *
- *   frc::PWMVictorSPX m_frontRight{3};
- *   frc::PWMVictorSPX m_rearRight{4};
- *   frc::MotorControllerGroup m_right{m_frontRight, m_rearRight};
- *
- *   frc::DifferentialDrive m_drive{m_left, m_right};
- * };
- * @endcode
- *
- * Six motor drivetrain:
- * @code{.cpp}
- * class Robot {
- *  public:
- *   frc::PWMVictorSPX m_frontLeft{1};
- *   frc::PWMVictorSPX m_midLeft{2};
- *   frc::PWMVictorSPX m_rearLeft{3};
- *   frc::MotorControllerGroup m_left{m_frontLeft, m_midLeft, m_rearLeft};
- *
- *   frc::PWMVictorSPX m_frontRight{4};
- *   frc::PWMVictorSPX m_midRight{5};
- *   frc::PWMVictorSPX m_rearRight{6};
- *   frc::MotorControllerGroup m_right{m_frontRight, m_midRight, m_rearRight};
- *
- *   frc::DifferentialDrive m_drive{m_left, m_right};
- * };
- * @endcode
+ * wheels per side (e.g., 6WD or 8WD). This class takes a setter per side. For
+ * four and six motor drivetrains, use CAN motor controller followers or
+ * PWMMotorController::AddFollower().
  *
  * A differential drive robot has left and right wheels separated by an
  * arbitrary width.
@@ -97,17 +65,39 @@
    * Uses normalized voltage [-1.0..1.0].
    */
   struct WheelSpeeds {
+    /// Left wheel speed.
     double left = 0.0;
+    /// Right wheel speed.
     double right = 0.0;
   };
 
+  WPI_IGNORE_DEPRECATED
+
+  /**
+   * Construct a DifferentialDrive.
+   *
+   * To pass multiple motors per side, use CAN motor controller followers or
+   * PWMSpeedController::AddFollower(). If a motor needs to be inverted, do so
+   * before passing it in.
+   *
+   * @param leftMotor Left motor.
+   * @param rightMotor Right motor.
+   */
+  DifferentialDrive(MotorController& leftMotor, MotorController& rightMotor);
+
+  WPI_UNIGNORE_DEPRECATED
+
   /**
    * Construct a DifferentialDrive.
    *
    * To pass multiple motors per side, use a MotorControllerGroup. If a motor
    * needs to be inverted, do so before passing it in.
+   *
+   * @param leftMotor Left motor setter.
+   * @param rightMotor Right motor setter.
    */
-  DifferentialDrive(MotorController& leftMotor, MotorController& rightMotor);
+  DifferentialDrive(std::function<void(double)> leftMotor,
+                    std::function<void(double)> rightMotor);
 
   ~DifferentialDrive() override = default;
 
@@ -210,8 +200,12 @@
   void InitSendable(wpi::SendableBuilder& builder) override;
 
  private:
-  MotorController* m_leftMotor;
-  MotorController* m_rightMotor;
+  std::function<void(double)> m_leftMotor;
+  std::function<void(double)> m_rightMotor;
+
+  // Used for Sendable property getters
+  double m_leftOutput = 0.0;
+  double m_rightOutput = 0.0;
 };
 
 }  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h b/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h
index f4c28f4..6d8ebac 100644
--- a/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h
+++ b/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h
@@ -4,10 +4,12 @@
 
 #pragma once
 
+#include <functional>
 #include <memory>
 #include <string>
 
 #include <units/angle.h>
+#include <wpi/deprecated.h>
 #include <wpi/sendable/Sendable.h>
 #include <wpi/sendable/SendableHelper.h>
 
@@ -63,21 +65,49 @@
    * Uses normalized voltage [-1.0..1.0].
    */
   struct WheelSpeeds {
+    /// Front-left wheel speed.
     double frontLeft = 0.0;
+    /// Front-right wheel speed.
     double frontRight = 0.0;
+    /// Rear-left wheel speed.
     double rearLeft = 0.0;
+    /// Rear-right wheel speed.
     double rearRight = 0.0;
   };
 
+  WPI_IGNORE_DEPRECATED
+
   /**
    * Construct a MecanumDrive.
    *
    * If a motor needs to be inverted, do so before passing it in.
+   *
+   * @param frontLeftMotor Front-left motor.
+   * @param rearLeftMotor Rear-left motor.
+   * @param frontRightMotor Front-right motor.
+   * @param rearRightMotor Rear-right motor.
    */
   MecanumDrive(MotorController& frontLeftMotor, MotorController& rearLeftMotor,
                MotorController& frontRightMotor,
                MotorController& rearRightMotor);
 
+  WPI_UNIGNORE_DEPRECATED
+
+  /**
+   * Construct a MecanumDrive.
+   *
+   * If a motor needs to be inverted, do so before passing it in.
+   *
+   * @param frontLeftMotor Front-left motor setter.
+   * @param rearLeftMotor Rear-left motor setter.
+   * @param frontRightMotor Front-right motor setter.
+   * @param rearRightMotor Rear-right motor setter.
+   */
+  MecanumDrive(std::function<void(double)> frontLeftMotor,
+               std::function<void(double)> rearLeftMotor,
+               std::function<void(double)> frontRightMotor,
+               std::function<void(double)> rearRightMotor);
+
   ~MecanumDrive() override = default;
 
   MecanumDrive(MecanumDrive&&) = default;
@@ -141,10 +171,16 @@
   void InitSendable(wpi::SendableBuilder& builder) override;
 
  private:
-  MotorController* m_frontLeftMotor;
-  MotorController* m_rearLeftMotor;
-  MotorController* m_frontRightMotor;
-  MotorController* m_rearRightMotor;
+  std::function<void(double)> m_frontLeftMotor;
+  std::function<void(double)> m_rearLeftMotor;
+  std::function<void(double)> m_frontRightMotor;
+  std::function<void(double)> m_rearRightMotor;
+
+  // Used for Sendable property getters
+  double m_frontLeftOutput = 0.0;
+  double m_rearLeftOutput = 0.0;
+  double m_frontRightOutput = 0.0;
+  double m_rearRightOutput = 0.0;
 
   bool reported = false;
 };
diff --git a/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h b/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h
index b3fb56b..2a74643 100644
--- a/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h
+++ b/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h
@@ -23,12 +23,19 @@
    * The location of a motor on the robot for the purpose of driving.
    */
   enum MotorType {
+    /// Front-left motor.
     kFrontLeft = 0,
+    /// Front-right motor.
     kFrontRight = 1,
+    /// Rear-left motor.
     kRearLeft = 2,
+    /// Rear-right motor.
     kRearRight = 3,
+    /// Left motor.
     kLeft = 0,
+    /// Right motor.
     kRight = 1,
+    /// Back motor.
     kBack = 2
   };
 
@@ -70,14 +77,23 @@
   std::string GetDescription() const override = 0;
 
  protected:
+  /// Default input deadband.
+  static constexpr double kDefaultDeadband = 0.02;
+
+  /// Default maximum output.
+  static constexpr double kDefaultMaxOutput = 1.0;
+
   /**
    * Renormalize all wheel speeds if the magnitude of any wheel is greater than
    * 1.0.
    */
   static void Desaturate(std::span<double> wheelSpeeds);
 
-  double m_deadband = 0.02;
-  double m_maxOutput = 1.0;
+  /// Input deadband.
+  double m_deadband = kDefaultDeadband;
+
+  /// Maximum output.
+  double m_maxOutput = kDefaultMaxOutput;
 };
 
 }  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/event/EventLoop.h b/wpilibc/src/main/native/include/frc/event/EventLoop.h
index 224dd3b..dca6122 100644
--- a/wpilibc/src/main/native/include/frc/event/EventLoop.h
+++ b/wpilibc/src/main/native/include/frc/event/EventLoop.h
@@ -38,5 +38,6 @@
 
  private:
   std::vector<wpi::unique_function<void()>> m_bindings;
+  bool m_running{false};
 };
 }  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/interfaces/Accelerometer.h b/wpilibc/src/main/native/include/frc/interfaces/Accelerometer.h
index 77f1d5b..ceafeba 100644
--- a/wpilibc/src/main/native/include/frc/interfaces/Accelerometer.h
+++ b/wpilibc/src/main/native/include/frc/interfaces/Accelerometer.h
@@ -20,7 +20,27 @@
   Accelerometer(Accelerometer&&) = default;
   Accelerometer& operator=(Accelerometer&&) = default;
 
-  enum Range { kRange_2G = 0, kRange_4G = 1, kRange_8G = 2, kRange_16G = 3 };
+  /**
+   * Accelerometer range.
+   */
+  enum Range {
+    /**
+     * 2 Gs max.
+     */
+    kRange_2G = 0,
+    /**
+     * 4 Gs max.
+     */
+    kRange_4G = 1,
+    /**
+     * 8 Gs max.
+     */
+    kRange_8G = 2,
+    /**
+     * 16 Gs max.
+     */
+    kRange_16G = 3
+  };
 
   /**
    * Common interface for setting the measuring range of an accelerometer.
diff --git a/wpilibc/src/main/native/include/frc/internal/DriverStationModeThread.h b/wpilibc/src/main/native/include/frc/internal/DriverStationModeThread.h
index f4fd11c..e646e15 100644
--- a/wpilibc/src/main/native/include/frc/internal/DriverStationModeThread.h
+++ b/wpilibc/src/main/native/include/frc/internal/DriverStationModeThread.h
@@ -8,9 +8,16 @@
 #include <thread>
 
 namespace frc::internal {
+/**
+ * For internal use only.
+ */
 class DriverStationModeThread {
  public:
+  /**
+   * For internal use only.
+   */
   DriverStationModeThread();
+
   ~DriverStationModeThread();
 
   DriverStationModeThread(const DriverStationModeThread& other) = delete;
@@ -19,9 +26,39 @@
       delete;
   DriverStationModeThread& operator=(DriverStationModeThread&& other) = delete;
 
-  void InAutonomous(bool entering);
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only.
+   *
+   * @param entering If true, starting disabled code; if false, leaving disabled
+   * code
+   */
   void InDisabled(bool entering);
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only.
+   *
+   * @param entering If true, starting autonomous code; if false, leaving
+   * autonomous code
+   */
+  void InAutonomous(bool entering);
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only.
+   *
+   * @param entering If true, starting teleop code; if false, leaving teleop
+   * code
+   */
   void InTeleop(bool entering);
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only.
+   *
+   * @param entering If true, starting test code; if false, leaving test code
+   */
   void InTest(bool entering);
 
  private:
diff --git a/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h b/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h
index 3714146..2f0a349 100644
--- a/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h
+++ b/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h
@@ -19,14 +19,14 @@
 class LiveWindow final {
  public:
   /**
-   * Set function to be called when LiveWindow is enabled.
+   * Sets function to be called when LiveWindow is enabled.
    *
    * @param func function (or nullptr for none)
    */
   static void SetEnabledCallback(std::function<void()> func);
 
   /**
-   * Set function to be called when LiveWindow is disabled.
+   * Sets function to be called when LiveWindow is disabled.
    *
    * @param func function (or nullptr for none)
    */
@@ -56,6 +56,11 @@
    */
   static void EnableAllTelemetry();
 
+  /**
+   * Returns true if LiveWindow is enabled.
+   *
+   * @return True if LiveWindow is enabled.
+   */
   static bool IsEnabled();
 
   /**
diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/MotorControllerGroup.h b/wpilibc/src/main/native/include/frc/motorcontrol/MotorControllerGroup.h
index 99a9e4e..6500fb3 100644
--- a/wpilibc/src/main/native/include/frc/motorcontrol/MotorControllerGroup.h
+++ b/wpilibc/src/main/native/include/frc/motorcontrol/MotorControllerGroup.h
@@ -7,23 +7,42 @@
 #include <functional>
 #include <vector>
 
+#include <wpi/deprecated.h>
 #include <wpi/sendable/Sendable.h>
 #include <wpi/sendable/SendableHelper.h>
 
 #include "frc/motorcontrol/MotorController.h"
 
+WPI_IGNORE_DEPRECATED
+
 namespace frc {
 
 /**
  * Allows multiple MotorController objects to be linked together.
  */
-class MotorControllerGroup : public wpi::Sendable,
-                             public MotorController,
-                             public wpi::SendableHelper<MotorControllerGroup> {
+class [[deprecated(
+    "Use PWMMotorController::AddFollower() or if using CAN motor controllers,"
+    "use their method of following.")]] MotorControllerGroup
+    : public wpi::Sendable,
+      public MotorController,
+      public wpi::SendableHelper<MotorControllerGroup> {
  public:
+  /**
+   * Create a new MotorControllerGroup with the provided MotorControllers.
+   *
+   * @tparam MotorControllers The MotorController types.
+   * @param motorController The first MotorController to add
+   * @param motorControllers The MotorControllers to add
+   */
   template <class... MotorControllers>
   explicit MotorControllerGroup(MotorController& motorController,
                                 MotorControllers&... motorControllers);
+
+  /**
+   * Create a new MotorControllerGroup with the provided MotorControllers.
+   *
+   * @param motorControllers The MotorControllers to add.
+   */
   explicit MotorControllerGroup(
       std::vector<std::reference_wrapper<MotorController>>&& motorControllers);
 
@@ -50,3 +69,5 @@
 }  // namespace frc
 
 #include "frc/motorcontrol/MotorControllerGroup.inc"
+
+WPI_UNIGNORE_DEPRECATED
diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/NidecBrushless.h b/wpilibc/src/main/native/include/frc/motorcontrol/NidecBrushless.h
index cc95d71..d50c836 100644
--- a/wpilibc/src/main/native/include/frc/motorcontrol/NidecBrushless.h
+++ b/wpilibc/src/main/native/include/frc/motorcontrol/NidecBrushless.h
@@ -6,6 +6,7 @@
 
 #include <string>
 
+#include <wpi/deprecated.h>
 #include <wpi/sendable/Sendable.h>
 #include <wpi/sendable/SendableHelper.h>
 
@@ -16,6 +17,8 @@
 
 namespace frc {
 
+WPI_IGNORE_DEPRECATED
+
 /**
  * Nidec Brushless Motor.
  */
@@ -95,4 +98,6 @@
   double m_speed = 0.0;
 };
 
+WPI_UNIGNORE_DEPRECATED
+
 }  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h b/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h
index bca5d7f..54a16bb 100644
--- a/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h
+++ b/wpilibc/src/main/native/include/frc/motorcontrol/PWMMotorController.h
@@ -4,9 +4,16 @@
 
 #pragma once
 
+#include <concepts>
+#include <memory>
 #include <string>
 #include <string_view>
+#include <type_traits>
+#include <utility>
+#include <vector>
 
+#include <units/voltage.h>
+#include <wpi/deprecated.h>
 #include <wpi/sendable/Sendable.h>
 #include <wpi/sendable/SendableHelper.h>
 
@@ -17,6 +24,8 @@
 namespace frc {
 class DMA;
 
+WPI_IGNORE_DEPRECATED
+
 /**
  * Common base class for all PWM Motor Controllers.
  */
@@ -41,6 +50,20 @@
   void Set(double value) override;
 
   /**
+   * Sets the voltage output of the PWMMotorController. Compensates for
+   * the current bus voltage to ensure that the desired voltage is output even
+   * if the battery voltage is below 12V - highly useful when the voltage
+   * outputs are "meaningful" (e.g. they come from a feedforward calculation).
+   *
+   * <p>NOTE: This function *must* be called regularly in order for voltage
+   * compensation to work properly - unlike the ordinary set function, it is not
+   * "set it and forget it."
+   *
+   * @param output The voltage to output.
+   */
+  void SetVoltage(units::volt_t output) override;
+
+  /**
    * Get the recently set value of the PWM. This value is affected by the
    * inversion property. If you want the value that is sent directly to the
    * MotorController, use PWM::GetSpeed() instead.
@@ -71,6 +94,24 @@
    */
   void EnableDeadbandElimination(bool eliminateDeadband);
 
+  /**
+   * Make the given PWM motor controller follow the output of this one.
+   *
+   * @param follower The motor controller follower.
+   */
+  void AddFollower(PWMMotorController& follower);
+
+  /**
+   * Make the given PWM motor controller follow the output of this one.
+   *
+   * @param follower The motor controller follower.
+   */
+  template <std::derived_from<PWMMotorController> T>
+  void AddFollower(T&& follower) {
+    m_owningFollowers.emplace_back(
+        std::make_unique<std::decay_t<T>>(std::forward<T>(follower)));
+  }
+
  protected:
   /**
    * Constructor for a PWM Motor %Controller connected via PWM.
@@ -83,12 +124,17 @@
 
   void InitSendable(wpi::SendableBuilder& builder) override;
 
+  /// PWM instances for motor controller.
   PWM m_pwm;
 
  private:
   bool m_isInverted = false;
+  std::vector<PWMMotorController*> m_nonowningFollowers;
+  std::vector<std::unique_ptr<PWMMotorController>> m_owningFollowers;
 
   PWM* GetPwm() { return &m_pwm; }
 };
 
+WPI_UNIGNORE_DEPRECATED
+
 }  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/motorcontrol/PWMSparkFlex.h b/wpilibc/src/main/native/include/frc/motorcontrol/PWMSparkFlex.h
new file mode 100644
index 0000000..3106921
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/motorcontrol/PWMSparkFlex.h
@@ -0,0 +1,41 @@
+// 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 "frc/motorcontrol/PWMMotorController.h"
+
+namespace frc {
+
+/**
+ * REV Robotics SPARK Flex Motor %Controller.
+ *
+ * Note that the SPARK Flex uses the following bounds for PWM values. These
+ * values should work reasonably well for most controllers, but if users
+ * experience issues such as asymmetric behavior around the deadband or
+ * inability to saturate the controller in either direction, calibration is
+ * recommended. The calibration procedure can be found in the SPARK Flex User
+ * Manual available from REV Robotics.
+ *
+ * \li 2.003ms = full "forward"
+ * \li 1.550ms = the "high end" of the deadband range
+ * \li 1.500ms = center of the deadband range (off)
+ * \li 1.460ms = the "low end" of the deadband range
+ * \li 0.999ms = full "reverse"
+ */
+class PWMSparkFlex : public PWMMotorController {
+ public:
+  /**
+   * Constructor for a SPARK Flex.
+   *
+   * @param channel The PWM channel that the SPARK Flex is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit PWMSparkFlex(int channel);
+
+  PWMSparkFlex(PWMSparkFlex&&) = default;
+  PWMSparkFlex& operator=(PWMSparkFlex&&) = default;
+};
+
+}  // namespace frc
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.h
index fc15948..8cb8673 100644
--- a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.h
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.h
@@ -26,6 +26,13 @@
 template <typename Derived>
 class ShuffleboardComponent : public ShuffleboardComponentBase {
  public:
+  /**
+   * Constructs a ShuffleboardComponent.
+   *
+   * @param parent The parent container.
+   * @param title The component title.
+   * @param type The component type.
+   */
   ShuffleboardComponent(ShuffleboardContainer& parent, std::string_view title,
                         std::string_view type = "");
 
diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardEventImportance.h b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardEventImportance.h
index 1fa9c91..ea251ec 100644
--- a/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardEventImportance.h
+++ b/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardEventImportance.h
@@ -14,6 +14,11 @@
 
 enum ShuffleboardEventImportance { kTrivial, kLow, kNormal, kHigh, kCritical };
 
+/**
+ * Returns name of the given enum.
+ *
+ * @return Name of the given enum.
+ */
 inline std::string_view ShuffleboardEventImportanceName(
     ShuffleboardEventImportance importance) {
   switch (importance) {
diff --git a/wpilibc/src/main/native/include/frc/simulation/ADXL345Sim.h b/wpilibc/src/main/native/include/frc/simulation/ADXL345Sim.h
index af96b39..3cf6162 100644
--- a/wpilibc/src/main/native/include/frc/simulation/ADXL345Sim.h
+++ b/wpilibc/src/main/native/include/frc/simulation/ADXL345Sim.h
@@ -14,7 +14,7 @@
 namespace sim {
 
 /**
- * Class to control a simulated ADXRS450 gyroscope.
+ * Class to control a simulated ADXL345.
  */
 class ADXL345Sim {
  public:
diff --git a/wpilibc/src/main/native/include/frc/simulation/ADXL362Sim.h b/wpilibc/src/main/native/include/frc/simulation/ADXL362Sim.h
index 269732b..cc63af2 100644
--- a/wpilibc/src/main/native/include/frc/simulation/ADXL362Sim.h
+++ b/wpilibc/src/main/native/include/frc/simulation/ADXL362Sim.h
@@ -13,7 +13,7 @@
 namespace sim {
 
 /**
- * Class to control a simulated ADXRS450 gyroscope.
+ * Class to control a simulated ADXL362.
  */
 class ADXL362Sim {
  public:
diff --git a/wpilibc/src/main/native/include/frc/simulation/DifferentialDrivetrainSim.h b/wpilibc/src/main/native/include/frc/simulation/DifferentialDrivetrainSim.h
index 78310d7..644e348 100644
--- a/wpilibc/src/main/native/include/frc/simulation/DifferentialDrivetrainSim.h
+++ b/wpilibc/src/main/native/include/frc/simulation/DifferentialDrivetrainSim.h
@@ -187,6 +187,13 @@
    */
   void SetPose(const frc::Pose2d& pose);
 
+  /**
+   * The differential drive dynamics function.
+   *
+   * @param x The state.
+   * @param u The input.
+   * @return The state derivative with respect to time.
+   */
   Vectord<7> Dynamics(const Vectord<7>& x, const Eigen::Vector2d& u);
 
   class State {
@@ -210,32 +217,54 @@
    */
   class KitbotGearing {
    public:
+    /// Gear ratio of 12.75:1.
     static constexpr double k12p75 = 12.75;
+    /// Gear ratio of 10.71:1.
     static constexpr double k10p71 = 10.71;
+    /// Gear ratio of 8.45:1.
     static constexpr double k8p45 = 8.45;
+    /// Gear ratio of 7.31:1.
     static constexpr double k7p31 = 7.31;
+    /// Gear ratio of 5.95:1.
     static constexpr double k5p95 = 5.95;
   };
 
+  /**
+   * Represents common motor layouts of the kit drivetrain.
+   */
   class KitbotMotor {
    public:
+    /// One CIM motor per drive side.
     static constexpr frc::DCMotor SingleCIMPerSide = frc::DCMotor::CIM(1);
+    /// Two CIM motors per drive side.
     static constexpr frc::DCMotor DualCIMPerSide = frc::DCMotor::CIM(2);
+    /// One Mini CIM motor per drive side.
     static constexpr frc::DCMotor SingleMiniCIMPerSide =
         frc::DCMotor::MiniCIM(1);
+    /// Two Mini CIM motors per drive side.
     static constexpr frc::DCMotor DualMiniCIMPerSide = frc::DCMotor::MiniCIM(2);
+    /// One Falcon 500 motor per drive side.
     static constexpr frc::DCMotor SingleFalcon500PerSide =
         frc::DCMotor::Falcon500(1);
+    /// Two Falcon 500 motors per drive side.
     static constexpr frc::DCMotor DualFalcon500PerSide =
         frc::DCMotor::Falcon500(2);
+    /// One NEO motor per drive side.
     static constexpr frc::DCMotor SingleNEOPerSide = frc::DCMotor::NEO(1);
+    /// Two NEO motors per drive side.
     static constexpr frc::DCMotor DualNEOPerSide = frc::DCMotor::NEO(2);
   };
 
+  /**
+   * Represents common wheel sizes of the kit drivetrain.
+   */
   class KitbotWheelSize {
    public:
+    /// Six inch diameter wheels.
     static constexpr units::meter_t kSixInch = 6_in;
+    /// Eight inch diameter wheels.
     static constexpr units::meter_t kEightInch = 8_in;
+    /// Ten inch diameter wheels.
     static constexpr units::meter_t kTenInch = 10_in;
   };
 
diff --git a/wpilibc/src/main/native/include/frc/simulation/GenericHIDSim.h b/wpilibc/src/main/native/include/frc/simulation/GenericHIDSim.h
index 399e0c1..ba56c4d 100644
--- a/wpilibc/src/main/native/include/frc/simulation/GenericHIDSim.h
+++ b/wpilibc/src/main/native/include/frc/simulation/GenericHIDSim.h
@@ -136,6 +136,7 @@
   double GetRumble(GenericHID::RumbleType type);
 
  protected:
+  /// GenericHID port.
   int m_port;
 };
 
diff --git a/wpilibc/src/main/native/include/frc/simulation/LinearSystemSim.h b/wpilibc/src/main/native/include/frc/simulation/LinearSystemSim.h
index cfc87b2..a4fec00 100644
--- a/wpilibc/src/main/native/include/frc/simulation/LinearSystemSim.h
+++ b/wpilibc/src/main/native/include/frc/simulation/LinearSystemSim.h
@@ -23,9 +23,9 @@
  * voltage). Call the Update() method to update the simulation. Set simulated
  * sensor readings with the simulated positions in the GetOutput() method.
  *
- * @tparam States  The number of states of the system.
- * @tparam Inputs  The number of inputs to the system.
- * @tparam Outputs The number of outputs of the system.
+ * @tparam States  Number of states of the system.
+ * @tparam Inputs  Number of inputs to the system.
+ * @tparam Outputs Number of outputs of the system.
  */
 template <int States, int Inputs, int Outputs>
 class LinearSystemSim {
@@ -140,11 +140,20 @@
         u, frc::RobotController::GetInputVoltage());
   }
 
+  /// The plant that represents the linear system.
   LinearSystem<States, Inputs, Outputs> m_plant;
 
+  /// State vector.
   Vectord<States> m_x;
-  Vectord<Outputs> m_y;
+
+  /// Input vector.
   Vectord<Inputs> m_u;
+
+  /// Output vector.
+  Vectord<Outputs> m_y;
+
+  /// The standard deviations of measurements, used for adding noise to the
+  /// measurements.
   std::array<double, Outputs> m_measurementStdDevs;
 };
 }  // namespace frc::sim
diff --git a/wpilibc/src/main/native/include/frc/simulation/PneumaticsBaseSim.h b/wpilibc/src/main/native/include/frc/simulation/PneumaticsBaseSim.h
index 510349f..f3000f4 100644
--- a/wpilibc/src/main/native/include/frc/simulation/PneumaticsBaseSim.h
+++ b/wpilibc/src/main/native/include/frc/simulation/PneumaticsBaseSim.h
@@ -177,9 +177,22 @@
   virtual void ResetData() = 0;
 
  protected:
+  /// PneumaticsBase index.
   const int m_index;
-  explicit PneumaticsBaseSim(const PneumaticsBase& module);
+
+  /**
+   * Constructs a PneumaticsBaseSim with the given index.
+   *
+   * @param index The index.
+   */
   explicit PneumaticsBaseSim(const int index);
+
+  /**
+   * Constructs a PneumaticsBaseSim for the given module.
+   *
+   * @param module The module.
+   */
+  explicit PneumaticsBaseSim(const PneumaticsBase& module);
 };
 
 }  // namespace frc::sim
diff --git a/wpilibc/src/main/native/include/frc/simulation/RoboRioSim.h b/wpilibc/src/main/native/include/frc/simulation/RoboRioSim.h
index 64e81e1..6471347 100644
--- a/wpilibc/src/main/native/include/frc/simulation/RoboRioSim.h
+++ b/wpilibc/src/main/native/include/frc/simulation/RoboRioSim.h
@@ -11,6 +11,7 @@
 #include <units/temperature.h>
 #include <units/voltage.h>
 
+#include "frc/RobotController.h"
 #include "frc/simulation/CallbackStore.h"
 
 namespace frc::sim {
@@ -515,6 +516,32 @@
   static void SetComments(std::string_view comments);
 
   /**
+   * Register a callback to be run whenever the Radio led state changes.
+   *
+   * @param callback the callback
+   * @param initialNotify whether the callback should be called with the
+   *                      initial value
+   * @return the CallbackStore object associated with this callback
+   */
+  [[nodiscard]]
+  static std::unique_ptr<CallbackStore> RegisterRadioLEDStateCallback(
+      NotifyCallback callback, bool initialNotify);
+
+  /**
+   * Get the state of the radio led.
+   *
+   * @return The state of the radio led.
+   */
+  static RadioLEDState GetRadioLEDState();
+
+  /**
+   * Set the state of the radio led.
+   *
+   * @param state The state of the radio led.
+   */
+  static void SetRadioLEDState(RadioLEDState state);
+
+  /**
    * Reset all simulation data.
    */
   static void ResetData();
diff --git a/wpilibc/src/main/native/include/frc/simulation/UltrasonicSim.h b/wpilibc/src/main/native/include/frc/simulation/UltrasonicSim.h
index 5db41f7..0d22d87 100644
--- a/wpilibc/src/main/native/include/frc/simulation/UltrasonicSim.h
+++ b/wpilibc/src/main/native/include/frc/simulation/UltrasonicSim.h
@@ -36,14 +36,14 @@
   /**
    * Sets if the range measurement is valid.
    *
-   * @param isValid True if valid
+   * @param valid True if valid
    */
-  void SetRangeValid(bool isValid);
+  void SetRangeValid(bool valid);
 
   /**
-   * Sets the range measurement
+   * Sets the range measurement.
    *
-   * @param range The range
+   * @param range The range.
    */
   void SetRange(units::inch_t range);
 
diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h
index baee6ff..2051d1b 100644
--- a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h
+++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h
@@ -21,6 +21,9 @@
 
 namespace frc {
 
+/**
+ * Implementation detail for SendableBuilder.
+ */
 class SendableBuilderImpl : public nt::NTSendableBuilder {
  public:
   SendableBuilderImpl() = default;
diff --git a/wpilibc/src/main/native/include/frc/sysid/SysIdRoutineLog.h b/wpilibc/src/main/native/include/frc/sysid/SysIdRoutineLog.h
new file mode 100644
index 0000000..7f106bd
--- /dev/null
+++ b/wpilibc/src/main/native/include/frc/sysid/SysIdRoutineLog.h
@@ -0,0 +1,194 @@
+// 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 <string>
+#include <string_view>
+#include <unordered_map>
+
+#include <units/acceleration.h>
+#include <units/angle.h>
+#include <units/angular_acceleration.h>
+#include <units/angular_velocity.h>
+#include <units/current.h>
+#include <units/length.h>
+#include <units/velocity.h>
+#include <units/voltage.h>
+#include <wpi/DataLog.h>
+
+namespace frc::sysid {
+
+/**
+ * Possible state of a SysId routine.
+ */
+enum class State {
+  /// Quasistatic forward test.
+  kQuasistaticForward,
+  /// Quasistatic reverse test.
+  kQuasistaticReverse,
+  /// Dynamic forward test.
+  kDynamicForward,
+  /// Dynamic reverse test.
+  kDynamicReverse,
+  /// No test.
+  kNone
+};
+
+/**
+ * Utility for logging data from a SysId test routine. Each complete routine
+ * (quasistatic and dynamic, forward and reverse) should have its own
+ * SysIdRoutineLog instance, with a unique log name.
+ */
+class SysIdRoutineLog {
+  using MotorEntries = wpi::StringMap<wpi::log::DoubleLogEntry>;
+  using LogEntries = wpi::StringMap<MotorEntries>;
+
+ public:
+  /** Logs data from a single motor during a SysIdRoutine. */
+  class MotorLog {
+   public:
+    /**
+     * Log a generic data value from the motor.
+     *
+     * @param name The name of the data field being recorded.
+     * @param value The numeric value of the data field.
+     * @param unit The unit string of the data field.
+     * @return The motor log (for call chaining).
+     */
+    MotorLog& value(std::string_view name, double value, std::string_view unit);
+
+    /**
+     * Log the voltage applied to the motor.
+     *
+     * @param voltage The voltage to record.
+     * @return The motor log (for call chaining).
+     */
+    MotorLog& voltage(units::volt_t voltage) {
+      return value("voltage", voltage.value(), voltage.name());
+    }
+
+    /**
+     * Log the linear position of the motor.
+     *
+     * @param position The linear position to record.
+     * @return The motor log (for call chaining).
+     */
+    MotorLog& position(units::meter_t position) {
+      return value("position", position.value(), position.name());
+    }
+
+    /**
+     * Log the angular position of the motor.
+     *
+     * @param position The angular position to record.
+     * @return The motor log (for call chaining).
+     */
+    MotorLog& position(units::turn_t position) {
+      return value("position", position.value(), position.name());
+    }
+
+    /**
+     * Log the linear velocity of the motor.
+     *
+     * @param velocity The linear velocity to record.
+     * @return The motor log (for call chaining).
+     */
+    MotorLog& velocity(units::meters_per_second_t velocity) {
+      return value("velocity", velocity.value(), velocity.name());
+    }
+
+    /**
+     * Log the angular velocity of the motor.
+     *
+     * @param velocity The angular velocity to record.
+     * @return The motor log (for call chaining).
+     */
+    MotorLog& velocity(units::turns_per_second_t velocity) {
+      return value("velocity", velocity.value(), velocity.name());
+    }
+
+    /**
+     * Log the linear acceleration of the motor.
+     *
+     * @param acceleration The linear acceleration to record.
+     * @return The motor log (for call chaining).
+     */
+    MotorLog& acceleration(units::meters_per_second_squared_t acceleration) {
+      return value("acceleration", acceleration.value(), acceleration.name());
+    }
+
+    /**
+     * Log the angular acceleration of the motor.
+     *
+     * @param acceleration The angular acceleration to record.
+     * @return The motor log (for call chaining).
+     */
+    MotorLog& acceleration(units::turns_per_second_squared_t acceleration) {
+      return value("acceleration", acceleration.value(), acceleration.name());
+    }
+
+    /**
+     * Log the current applied to the motor.
+     *
+     * @param current The current to record.
+     * @return The motor log (for call chaining).
+     */
+    MotorLog& current(units::ampere_t current) {
+      return value("current", current.value(), current.name());
+    }
+
+   private:
+    friend class SysIdRoutineLog;
+    /**
+     * Create a new SysId motor log handle.
+     *
+     * @param motorName The name of the motor whose data is being logged.
+     * @param logName The name of the SysIdRoutineLog that this motor belongs
+     * to.
+     * @param logEntries The DataLog entries of the SysIdRoutineLog that this
+     * motor belongs to.
+     */
+    MotorLog(std::string_view motorName, std::string_view logName,
+             LogEntries* logEntries);
+    std::string m_motorName;
+    std::string m_logName;
+    LogEntries* m_logEntries;
+  };
+
+  /**
+   * Create a new logging utility for a SysId test routine.
+   *
+   * @param logName The name for the test routine in the log. Should be unique
+   *   between complete test routines (quasistatic and dynamic, forward and
+   *   reverse). The current state of this test (e.g. "quasistatic-forward")
+   *   will appear in WPILog under the "sysid-test-state-logName" entry.
+   */
+  explicit SysIdRoutineLog(std::string_view logName);
+
+  /**
+   * Records the current state of the SysId test routine. Should be called once
+   * per iteration during tests with the type of the current test, and once upon
+   * test end with state `none`.
+   *
+   * @param state The current state of the SysId test routine.
+   */
+  void RecordState(State state);
+
+  /**
+   * Log data from a motor during a SysId routine.
+   *
+   * @param motorName The name of the motor.
+   * @return Handle with chainable callbacks to log individual data fields.
+   */
+  MotorLog Motor(std::string_view motorName);
+
+  static std::string StateEnumToString(State state);
+
+ private:
+  LogEntries m_logEntries;
+  std::string m_logName;
+  wpi::log::StringLogEntry m_state;
+};
+}  // namespace frc::sysid
diff --git a/wpilibc/src/main/native/include/frc/util/Color.h b/wpilibc/src/main/native/include/frc/util/Color.h
index 87d8c12..f51d3b1 100644
--- a/wpilibc/src/main/native/include/frc/util/Color.h
+++ b/wpilibc/src/main/native/include/frc/util/Color.h
@@ -5,7 +5,14 @@
 #pragma once
 
 #include <algorithm>
+#include <stdexcept>
 #include <string>
+#include <string_view>
+
+#include <fmt/core.h>
+#include <gcem.hpp>
+#include <wpi/StringExtras.h>
+#include <wpi/ct_string.h>
 
 namespace frc {
 
@@ -739,6 +746,9 @@
    */
   static const Color kYellowGreen;
 
+  /**
+   * Constructs a default color (black).
+   */
   constexpr Color() = default;
 
   /**
@@ -763,6 +773,33 @@
   constexpr Color(int r, int g, int b)
       : Color(r / 255.0, g / 255.0, b / 255.0) {}
 
+  /**
+   * Constructs a Color from a hex string.
+   *
+   * @param hexString a string of the format <tt>\#RRGGBB</tt>
+   * @throws std::invalid_argument if the hex string is invalid.
+   */
+  explicit constexpr Color(std::string_view hexString) {
+    if (hexString.length() != 7 || !hexString.starts_with("#") ||
+        !wpi::isHexDigit(hexString[1]) || !wpi::isHexDigit(hexString[2]) ||
+        !wpi::isHexDigit(hexString[3]) || !wpi::isHexDigit(hexString[4]) ||
+        !wpi::isHexDigit(hexString[5]) || !wpi::isHexDigit(hexString[6])) {
+      throw std::invalid_argument(
+          fmt::format("Invalid hex string for Color \"{}\"", hexString));
+    }
+
+    int r = wpi::hexDigitValue(hexString[1]) * 16 +
+            wpi::hexDigitValue(hexString[2]);
+    int g = wpi::hexDigitValue(hexString[3]) * 16 +
+            wpi::hexDigitValue(hexString[4]);
+    int b = wpi::hexDigitValue(hexString[5]) * 16 +
+            wpi::hexDigitValue(hexString[6]);
+
+    red = r / 255.0;
+    green = g / 255.0;
+    blue = b / 255.0;
+  }
+
   constexpr bool operator==(const Color&) const = default;
 
   /**
@@ -816,19 +853,29 @@
    *
    * @return a string of the format <tt>\#RRGGBB</tt>
    */
-  std::string HexString() const;
+  constexpr auto HexString() const {
+    const int r = 255.0 * red;
+    const int g = 255.0 * green;
+    const int b = 255.0 * blue;
 
+    return wpi::ct_string<char, std::char_traits<char>, 7>{
+        {'#', wpi::hexdigit(r / 16), wpi::hexdigit(r % 16),
+         wpi::hexdigit(g / 16), wpi::hexdigit(g % 16), wpi::hexdigit(b / 16),
+         wpi::hexdigit(b % 16)}};
+  }
+
+  /// Red component (0-1).
   double red = 0.0;
+
+  /// Green component (0-1).
   double green = 0.0;
+
+  /// Blue component (0-1).
   double blue = 0.0;
 
  private:
-  static constexpr double kPrecision = 1.0 / (1 << 12);
-
   static constexpr double roundAndClamp(double value) {
-    const auto rounded =
-        (static_cast<int>(value / kPrecision) + 0.5) * kPrecision;
-    return std::clamp(rounded, 0.0, 1.0);
+    return std::clamp(gcem::ceil(value * (1 << 12)) / (1 << 12), 0.0, 1.0);
   }
 };
 
diff --git a/wpilibc/src/main/native/include/frc/util/Color8Bit.h b/wpilibc/src/main/native/include/frc/util/Color8Bit.h
index 10afead..f4bc104 100644
--- a/wpilibc/src/main/native/include/frc/util/Color8Bit.h
+++ b/wpilibc/src/main/native/include/frc/util/Color8Bit.h
@@ -5,7 +5,13 @@
 #pragma once
 
 #include <algorithm>
+#include <stdexcept>
 #include <string>
+#include <string_view>
+
+#include <fmt/core.h>
+#include <wpi/StringExtras.h>
+#include <wpi/ct_string.h>
 
 #include "Color.h"
 
@@ -16,6 +22,9 @@
  */
 class Color8Bit {
  public:
+  /**
+   * Constructs a default color (black).
+   */
   constexpr Color8Bit() = default;
 
   /**
@@ -40,21 +49,79 @@
         green(color.green * 255),
         blue(color.blue * 255) {}
 
+  /**
+   * Constructs a Color8Bit from a hex string.
+   *
+   * @param hexString a string of the format <tt>\#RRGGBB</tt>
+   * @throws std::invalid_argument if the hex string is invalid.
+   */
+  explicit constexpr Color8Bit(std::string_view hexString) {
+    if (hexString.length() != 7 || !hexString.starts_with("#") ||
+        !wpi::isHexDigit(hexString[1]) || !wpi::isHexDigit(hexString[2]) ||
+        !wpi::isHexDigit(hexString[3]) || !wpi::isHexDigit(hexString[4]) ||
+        !wpi::isHexDigit(hexString[5]) || !wpi::isHexDigit(hexString[6])) {
+      throw std::invalid_argument(
+          fmt::format("Invalid hex string for Color \"{}\"", hexString));
+    }
+
+    red = wpi::hexDigitValue(hexString[1]) * 16 +
+          wpi::hexDigitValue(hexString[2]);
+    green = wpi::hexDigitValue(hexString[3]) * 16 +
+            wpi::hexDigitValue(hexString[4]);
+    blue = wpi::hexDigitValue(hexString[5]) * 16 +
+           wpi::hexDigitValue(hexString[6]);
+  }
+
+  constexpr bool operator==(const Color8Bit&) const = default;
+
   constexpr operator Color() const {  // NOLINT
     return Color(red / 255.0, green / 255.0, blue / 255.0);
   }
 
-  constexpr bool operator==(const Color8Bit&) const = default;
+  /**
+   * Create a Color8Bit from a hex string.
+   *
+   * @param hexString a string of the format <tt>\#RRGGBB</tt>
+   * @return Color8Bit object from hex string.
+   * @throws std::invalid_argument if the hex string is invalid.
+   */
+  static constexpr Color8Bit FromHexString(std::string_view hexString) {
+    if (hexString.length() != 7 || !hexString.starts_with("#") ||
+        !wpi::isHexDigit(hexString[1]) || !wpi::isHexDigit(hexString[2]) ||
+        !wpi::isHexDigit(hexString[3]) || !wpi::isHexDigit(hexString[4]) ||
+        !wpi::isHexDigit(hexString[5]) || !wpi::isHexDigit(hexString[6])) {
+      throw std::invalid_argument(
+          fmt::format("Invalid hex string for Color \"{}\"", hexString));
+    }
+
+    int r = wpi::hexDigitValue(hexString[0]) * 16 +
+            wpi::hexDigitValue(hexString[1]);
+    int g = wpi::hexDigitValue(hexString[2]) * 16 +
+            wpi::hexDigitValue(hexString[3]);
+    int b = wpi::hexDigitValue(hexString[4]) * 16 +
+            wpi::hexDigitValue(hexString[5]);
+    return Color8Bit{r, g, b};
+  }
 
   /**
    * Return this color represented as a hex string.
    *
    * @return a string of the format <tt>\#RRGGBB</tt>
    */
-  std::string HexString() const;
+  constexpr auto HexString() const {
+    return wpi::ct_string<char, std::char_traits<char>, 7>{
+        {'#', wpi::hexdigit(red / 16), wpi::hexdigit(red % 16),
+         wpi::hexdigit(green / 16), wpi::hexdigit(green % 16),
+         wpi::hexdigit(blue / 16), wpi::hexdigit(blue % 16)}};
+  }
 
+  /// Red component (0-255).
   int red = 0;
+
+  /// Green component (0-255).
   int green = 0;
+
+  /// Blue component (0-255).
   int blue = 0;
 };