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/wpilibcExamples/CMakeLists.txt b/wpilibcExamples/CMakeLists.txt
index f46d1c2..4554b94 100644
--- a/wpilibcExamples/CMakeLists.txt
+++ b/wpilibcExamples/CMakeLists.txt
@@ -7,29 +7,53 @@
 subdir_list(EXAMPLES  ${CMAKE_SOURCE_DIR}/wpilibcExamples/src/main/cpp/examples)
 
 foreach(example ${EXAMPLES})
-  file(GLOB_RECURSE sources src/main/cpp/examples/${example}/cpp/*.cpp
-                            src/main/cpp/examples/${example}/c/*.c)
-  add_executable(${example} ${sources})
-  wpilib_target_warnings(${example})
-  target_include_directories(${example} PUBLIC src/main/cpp/examples/${example}/include)
-  target_link_libraries(${example} apriltag wpilibc wpilibNewCommands romiVendordep xrpVendordep)
+    file(
+        GLOB_RECURSE sources
+        src/main/cpp/examples/${example}/cpp/*.cpp
+        src/main/cpp/examples/${example}/c/*.c
+    )
+    add_executable(${example} ${sources})
+    wpilib_target_warnings(${example})
+    target_include_directories(${example} PUBLIC src/main/cpp/examples/${example}/include)
+    target_link_libraries(
+        ${example}
+        apriltag
+        wpilibc
+        wpilibNewCommands
+        romiVendordep
+        xrpVendordep
+    )
 
-  if (WITH_TESTS AND EXISTS ${CMAKE_SOURCE_DIR}/wpilibcExamples/src/test/cpp/examples/${example})
-    wpilib_add_test(${example} src/test/cpp/examples/${example}/cpp)
-    target_sources(${example}_test PRIVATE ${sources})
-    target_include_directories(${example}_test PRIVATE
-                               src/main/cpp/examples/${example}/include
-                               src/test/cpp/examples/${example}/include)
-    target_compile_definitions(${example}_test PUBLIC RUNNING_FRC_TESTS)
-    target_link_libraries(${example}_test apriltag wpilibc wpilibNewCommands romiVendordep xrpVendordep gmock_main)
-  endif()
+    if(WITH_TESTS AND EXISTS ${CMAKE_SOURCE_DIR}/wpilibcExamples/src/test/cpp/examples/${example})
+        wpilib_add_test(${example} src/test/cpp/examples/${example}/cpp)
+        target_sources(${example}_test PRIVATE ${sources})
+        target_include_directories(
+            ${example}_test
+            PRIVATE
+                src/main/cpp/examples/${example}/include
+                src/test/cpp/examples/${example}/include
+        )
+        target_compile_definitions(${example}_test PUBLIC RUNNING_FRC_TESTS)
+        target_link_libraries(
+            ${example}_test
+            apriltag
+            wpilibc
+            wpilibNewCommands
+            romiVendordep
+            xrpVendordep
+            gmock_main
+        )
+    endif()
 endforeach()
 
 foreach(template ${TEMPLATES})
-  file(GLOB_RECURSE sources src/main/cpp/templates/${template}/cpp/*.cpp
-                            src/main/cpp/templates/${template}/c/*.c)
-  add_executable(${template} ${sources})
-  wpilib_target_warnings(${template})
-  target_include_directories(${template} PUBLIC src/main/cpp/templates/${template}/include)
-  target_link_libraries(${template} wpilibc wpilibNewCommands romiVendordep xrpVendordep)
+    file(
+        GLOB_RECURSE sources
+        src/main/cpp/templates/${template}/cpp/*.cpp
+        src/main/cpp/templates/${template}/c/*.c
+    )
+    add_executable(${template} ${sources})
+    wpilib_target_warnings(${template})
+    target_include_directories(${template} PUBLIC src/main/cpp/templates/${template}/include)
+    target_link_libraries(${template} wpilibc wpilibNewCommands romiVendordep xrpVendordep)
 endforeach()
diff --git a/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp
index 0ed53fd..443bdd8 100644
--- a/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp
@@ -37,13 +37,13 @@
  private:
   static void VisionThread() {
     frc::AprilTagDetector detector;
-    // look for tag16h5, don't correct any error bits
-    detector.AddFamily("tag16h5", 0);
+    // look for tag36h11, correct 7 error bits
+    detector.AddFamily("tag36h11", 7);
 
     // Set up Pose Estimator - parameters are for a Microsoft Lifecam HD-3000
     // (https://www.chiefdelphi.com/t/wpilib-apriltagdetector-sample-code/421411/21)
     frc::AprilTagPoseEstimator::Config poseEstConfig = {
-        .tagSize = units::length::inch_t(6.0),
+        .tagSize = units::length::inch_t(6.5),
         .fx = 699.3778103158814,
         .fy = 677.7161226393544,
         .cx = 345.6059345433618,
diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp
index b636b44..9c8d640 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp
@@ -14,10 +14,17 @@
 class Robot : public frc::TimedRobot {
   frc::PWMSparkMax m_leftMotor{0};
   frc::PWMSparkMax m_rightMotor{1};
-  frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor};
+  frc::DifferentialDrive m_robotDrive{
+      [&](double output) { m_leftMotor.Set(output); },
+      [&](double output) { m_rightMotor.Set(output); }};
   frc::Joystick m_stick{0};
 
  public:
+  Robot() {
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);
+  }
+
   void RobotInit() override {
     // We need to invert one side of the drivetrain so that positive voltages
     // result in both sides moving forward. Depending on how your robot's
diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp
index 23c9a56..38ff862 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp
@@ -14,10 +14,17 @@
 class Robot : public frc::TimedRobot {
   frc::PWMSparkMax m_leftMotor{0};
   frc::PWMSparkMax m_rightMotor{1};
-  frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor};
+  frc::DifferentialDrive m_robotDrive{
+      [&](double output) { m_leftMotor.Set(output); },
+      [&](double output) { m_rightMotor.Set(output); }};
   frc::XboxController m_driverController{0};
 
  public:
+  Robot() {
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);
+  }
+
   void RobotInit() override {
     // We need to invert one side of the drivetrain so that positive voltages
     // result in both sides moving forward. Depending on how your robot's
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/Robot.cpp
index d3a106b..13eb9f9 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/Robot.cpp
@@ -39,7 +39,7 @@
 void Robot::AutonomousInit() {
   m_autonomousCommand = m_container.GetAutonomousCommand();
 
-  if (m_autonomousCommand != nullptr) {
+  if (m_autonomousCommand) {
     m_autonomousCommand->Schedule();
   }
 }
@@ -51,9 +51,9 @@
   // teleop starts running. If you want the autonomous to
   // continue until interrupted by another command, remove
   // this line or comment it out.
-  if (m_autonomousCommand != nullptr) {
+  if (m_autonomousCommand) {
     m_autonomousCommand->Cancel();
-    m_autonomousCommand = nullptr;
+    m_autonomousCommand.reset();
   }
 }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp
index 90aa789..1bf4dcf 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp
@@ -60,6 +60,6 @@
   m_arm.Disable();
 }
 
-frc2::Command* RobotContainer::GetAutonomousCommand() {
-  return nullptr;
+frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
+  return frc2::cmd::None();
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp
index aeeac3d..1352295 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp
@@ -13,13 +13,20 @@
       m_right2{kRightMotor2Port},
       m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
       m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} {
+  wpi::SendableRegistry::AddChild(&m_drive, &m_left1);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_right1);
+
+  m_left1.AddFollower(m_left2);
+  m_right1.AddFollower(m_right2);
+
   // Set the distance per pulse for the encoders
   m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
   m_rightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
+
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
-  m_rightMotors.SetInverted(true);
+  m_right1.SetInverted(true);
 }
 
 void DriveSubsystem::Periodic() {
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Constants.h
index cff3932..556ee4c 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Constants.h
@@ -21,54 +21,54 @@
  */
 
 namespace DriveConstants {
-constexpr int kLeftMotor1Port = 0;
-constexpr int kLeftMotor2Port = 1;
-constexpr int kRightMotor1Port = 2;
-constexpr int kRightMotor2Port = 3;
+inline constexpr int kLeftMotor1Port = 0;
+inline constexpr int kLeftMotor2Port = 1;
+inline constexpr int kRightMotor1Port = 2;
+inline constexpr int kRightMotor2Port = 3;
 
-constexpr int kLeftEncoderPorts[]{0, 1};
-constexpr int kRightEncoderPorts[]{2, 3};
-constexpr bool kLeftEncoderReversed = false;
-constexpr bool kRightEncoderReversed = true;
+inline constexpr int kLeftEncoderPorts[]{0, 1};
+inline constexpr int kRightEncoderPorts[]{2, 3};
+inline constexpr bool kLeftEncoderReversed = false;
+inline constexpr bool kRightEncoderReversed = true;
 
-constexpr int kEncoderCPR = 1024;
-constexpr double kWheelDiameterInches = 6;
-constexpr double kEncoderDistancePerPulse =
+inline constexpr int kEncoderCPR = 1024;
+inline constexpr double kWheelDiameterInches = 6;
+inline constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
     (kWheelDiameterInches * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 }  // namespace DriveConstants
 
 namespace ArmConstants {
-constexpr int kMotorPort = 4;
+inline constexpr int kMotorPort = 4;
 
-constexpr double kP = 1;
+inline constexpr double kP = 1;
 
 // These are fake gains; in actuality these must be determined individually for
 // each robot
-constexpr auto kS = 1_V;
-constexpr auto kG = 1_V;
-constexpr auto kV = 0.5_V * 1_s / 1_rad;
-constexpr auto kA = 0.1_V * 1_s * 1_s / 1_rad;
+inline constexpr auto kS = 1_V;
+inline constexpr auto kG = 1_V;
+inline constexpr auto kV = 0.5_V * 1_s / 1_rad;
+inline constexpr auto kA = 0.1_V * 1_s * 1_s / 1_rad;
 
-constexpr auto kMaxVelocity = 3_rad_per_s;
-constexpr auto kMaxAcceleration = 10_rad / (1_s * 1_s);
+inline constexpr auto kMaxVelocity = 3_rad_per_s;
+inline constexpr auto kMaxAcceleration = 10_rad / (1_s * 1_s);
 
-constexpr int kEncoderPorts[]{4, 5};
-constexpr int kEncoderPPR = 256;
-constexpr auto kEncoderDistancePerPulse =
+inline constexpr int kEncoderPorts[]{4, 5};
+inline constexpr int kEncoderPPR = 256;
+inline constexpr auto kEncoderDistancePerPulse =
     2.0_rad * std::numbers::pi / kEncoderPPR;
 
 // The offset of the arm from the horizontal in its neutral position,
 // measured from the horizontal
-constexpr auto kArmOffset = 0.5_rad;
+inline constexpr auto kArmOffset = 0.5_rad;
 }  // namespace ArmConstants
 
 namespace AutoConstants {
-constexpr auto kAutoTimeoutSeconds = 12_s;
-constexpr auto kAutoShootTimeSeconds = 7_s;
+inline constexpr auto kAutoTimeoutSeconds = 12_s;
+inline constexpr auto kAutoShootTimeSeconds = 7_s;
 }  // namespace AutoConstants
 
 namespace OIConstants {
-constexpr int kDriverControllerPort = 0;
+inline constexpr int kDriverControllerPort = 0;
 }  // namespace OIConstants
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Robot.h
index a82f2ac..de9c814 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Robot.h
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Robot.h
@@ -4,6 +4,8 @@
 
 #pragma once
 
+#include <optional>
+
 #include <frc/TimedRobot.h>
 #include <frc2/command/Command.h>
 
@@ -24,7 +26,7 @@
  private:
   // Have it null by default so that if testing teleop it
   // doesn't have undefined behavior and potentially crash.
-  frc2::Command* m_autonomousCommand = nullptr;
+  std::optional<frc2::CommandPtr> m_autonomousCommand;
 
   RobotContainer m_container;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/RobotContainer.h
index 67d194c..ab77985 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/RobotContainer.h
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/RobotContainer.h
@@ -5,6 +5,7 @@
 #pragma once
 
 #include <frc2/command/Command.h>
+#include <frc2/command/CommandPtr.h>
 #include <frc2/command/button/CommandXboxController.h>
 
 #include "Constants.h"
@@ -28,7 +29,7 @@
    */
   void DisablePIDSubsystems();
 
-  frc2::Command* GetAutonomousCommand();
+  frc2::CommandPtr GetAutonomousCommand();
 
  private:
   // The driver's controller
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/subsystems/DriveSubsystem.h
index 47bf28e..47d3f3d 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/subsystems/DriveSubsystem.h
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/subsystems/DriveSubsystem.h
@@ -6,7 +6,6 @@
 
 #include <frc/Encoder.h>
 #include <frc/drive/DifferentialDrive.h>
-#include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <frc2/command/SubsystemBase.h>
 
@@ -75,14 +74,9 @@
   frc::PWMSparkMax m_right1;
   frc::PWMSparkMax m_right2;
 
-  // The motors on the left side of the drive
-  frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
-
-  // The motors on the right side of the drive
-  frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
-
   // The robot's drive
-  frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
+  frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); },
+                                 [&](double output) { m_right1.Set(output); }};
 
   // The left-side drive encoder
   frc::Encoder m_leftEncoder;
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/Robot.cpp
index c7eab48..c4c1661 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/Robot.cpp
@@ -37,7 +37,7 @@
 void Robot::AutonomousInit() {
   m_autonomousCommand = m_container.GetAutonomousCommand();
 
-  if (m_autonomousCommand != nullptr) {
+  if (m_autonomousCommand) {
     m_autonomousCommand->Schedule();
   }
 }
@@ -49,9 +49,9 @@
   // teleop starts running. If you want the autonomous to
   // continue until interrupted by another command, remove
   // this line or comment it out.
-  if (m_autonomousCommand != nullptr) {
+  if (m_autonomousCommand) {
     m_autonomousCommand->Cancel();
-    m_autonomousCommand = nullptr;
+    m_autonomousCommand.reset();
   }
 }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp
index dce4b95..a870416 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp
@@ -4,6 +4,7 @@
 
 #include "RobotContainer.h"
 
+#include <frc2/command/Commands.h>
 #include <units/angle.h>
 
 RobotContainer::RobotContainer() {
@@ -34,6 +35,6 @@
       .OnFalse(m_drive.SetMaxOutputCommand(1.0));
 }
 
-frc2::Command* RobotContainer::GetAutonomousCommand() {
-  return nullptr;
+frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
+  return frc2::cmd::None();
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp
index 16409ad..236d468 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp
@@ -13,13 +13,20 @@
       m_right2{kRightMotor2Port},
       m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
       m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} {
+  wpi::SendableRegistry::AddChild(&m_drive, &m_left1);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_right1);
+
+  m_left1.AddFollower(m_left2);
+  m_right1.AddFollower(m_right2);
+
   // Set the distance per pulse for the encoders
   m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
   m_rightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
+
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
-  m_rightMotors.SetInverted(true);
+  m_right1.SetInverted(true);
 }
 
 void DriveSubsystem::Periodic() {
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Constants.h
index cff3932..b91fe19 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Constants.h
@@ -21,52 +21,52 @@
  */
 
 namespace DriveConstants {
-constexpr int kLeftMotor1Port = 0;
-constexpr int kLeftMotor2Port = 1;
-constexpr int kRightMotor1Port = 2;
-constexpr int kRightMotor2Port = 3;
+inline constexpr int kLeftMotor1Port = 0;
+inline constexpr int kLeftMotor2Port = 1;
+inline constexpr int kRightMotor1Port = 2;
+inline constexpr int kRightMotor2Port = 3;
 
-constexpr int kLeftEncoderPorts[]{0, 1};
-constexpr int kRightEncoderPorts[]{2, 3};
-constexpr bool kLeftEncoderReversed = false;
-constexpr bool kRightEncoderReversed = true;
+inline constexpr int kLeftEncoderPorts[]{0, 1};
+inline constexpr int kRightEncoderPorts[]{2, 3};
+inline constexpr bool kLeftEncoderReversed = false;
+inline constexpr bool kRightEncoderReversed = true;
 
-constexpr int kEncoderCPR = 1024;
-constexpr double kWheelDiameterInches = 6;
-constexpr double kEncoderDistancePerPulse =
+inline constexpr int kEncoderCPR = 1024;
+inline constexpr double kWheelDiameterInches = 6;
+inline constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
     (kWheelDiameterInches * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 }  // namespace DriveConstants
 
 namespace ArmConstants {
-constexpr int kMotorPort = 4;
+inline constexpr int kMotorPort = 4;
 
-constexpr double kP = 1;
+inline constexpr double kP = 1;
 
 // These are fake gains; in actuality these must be determined individually for
 // each robot
-constexpr auto kS = 1_V;
-constexpr auto kG = 1_V;
-constexpr auto kV = 0.5_V * 1_s / 1_rad;
-constexpr auto kA = 0.1_V * 1_s * 1_s / 1_rad;
+inline constexpr auto kS = 1_V;
+inline constexpr auto kG = 1_V;
+inline constexpr auto kV = 0.5_V * 1_s / 1_rad;
+inline constexpr auto kA = 0.1_V * 1_s * 1_s / 1_rad;
 
-constexpr auto kMaxVelocity = 3_rad_per_s;
-constexpr auto kMaxAcceleration = 10_rad / (1_s * 1_s);
+inline constexpr auto kMaxVelocity = 3_rad_per_s;
+inline constexpr auto kMaxAcceleration = 10_rad / (1_s * 1_s);
 
-constexpr int kEncoderPorts[]{4, 5};
-constexpr int kEncoderPPR = 256;
-constexpr auto kEncoderDistancePerPulse =
+inline constexpr int kEncoderPorts[]{4, 5};
+inline constexpr int kEncoderPPR = 256;
+inline constexpr auto kEncoderDistancePerPulse =
     2.0_rad * std::numbers::pi / kEncoderPPR;
 
 // The offset of the arm from the horizontal in its neutral position,
 // measured from the horizontal
-constexpr auto kArmOffset = 0.5_rad;
+inline constexpr auto kArmOffset = 0.5_rad;
 }  // namespace ArmConstants
 
 namespace AutoConstants {
-constexpr auto kAutoTimeoutSeconds = 12_s;
-constexpr auto kAutoShootTimeSeconds = 7_s;
+inline constexpr auto kAutoTimeoutSeconds = 12_s;
+inline constexpr auto kAutoShootTimeSeconds = 7_s;
 }  // namespace AutoConstants
 
 namespace OIConstants {
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/ExampleSmartMotorController.h b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/ExampleSmartMotorController.h
index 5d55839..bd48d88 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/ExampleSmartMotorController.h
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/ExampleSmartMotorController.h
@@ -4,15 +4,13 @@
 
 #pragma once
 
-#include <frc/motorcontrol/MotorController.h>
-
 /**
  * A simplified stub class that simulates the API of a common "smart" motor
  * controller.
  *
  * <p>Has no actual functionality.
  */
-class ExampleSmartMotorController : public frc::MotorController {
+class ExampleSmartMotorController {
  public:
   enum PIDMode { kPosition, kVelocity, kMovementWitchcraft };
 
@@ -68,15 +66,15 @@
    */
   void ResetEncoder() {}
 
-  void Set(double speed) override {}
+  void Set(double speed) {}
 
-  double Get() const override { return 0; }
+  double Get() const { return 0; }
 
-  void SetInverted(bool isInverted) override {}
+  void SetInverted(bool isInverted) {}
 
-  bool GetInverted() const override { return false; }
+  bool GetInverted() const { return false; }
 
-  void Disable() override {}
+  void Disable() {}
 
-  void StopMotor() override {}
+  void StopMotor() {}
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Robot.h
index a82f2ac..de9c814 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Robot.h
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Robot.h
@@ -4,6 +4,8 @@
 
 #pragma once
 
+#include <optional>
+
 #include <frc/TimedRobot.h>
 #include <frc2/command/Command.h>
 
@@ -24,7 +26,7 @@
  private:
   // Have it null by default so that if testing teleop it
   // doesn't have undefined behavior and potentially crash.
-  frc2::Command* m_autonomousCommand = nullptr;
+  std::optional<frc2::CommandPtr> m_autonomousCommand;
 
   RobotContainer m_container;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/RobotContainer.h
index 08a4dbe..7668c03 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/RobotContainer.h
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/RobotContainer.h
@@ -5,6 +5,7 @@
 #pragma once
 
 #include <frc2/command/Command.h>
+#include <frc2/command/CommandPtr.h>
 #include <frc2/command/button/CommandXboxController.h>
 
 #include "Constants.h"
@@ -24,7 +25,7 @@
  public:
   RobotContainer();
 
-  frc2::Command* GetAutonomousCommand();
+  frc2::CommandPtr GetAutonomousCommand();
 
  private:
   // The driver's controller
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h
index 6830b96..ca7e28e 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h
@@ -8,7 +8,6 @@
 
 #include <frc/Encoder.h>
 #include <frc/drive/DifferentialDrive.h>
-#include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <frc2/command/Commands.h>
 #include <frc2/command/SubsystemBase.h>
@@ -73,14 +72,9 @@
   frc::PWMSparkMax m_right1;
   frc::PWMSparkMax m_right2;
 
-  // The motors on the left side of the drive
-  frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
-
-  // The motors on the right side of the drive
-  frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
-
   // The robot's drive
-  frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
+  frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); },
+                                 [&](double output) { m_right1.Set(output); }};
 
   // The left-side drive encoder
   frc::Encoder m_leftEncoder;
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Constants.h
index 0018a8a..c5883db 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Constants.h
@@ -22,25 +22,25 @@
  * they are needed.
  */
 
-static constexpr int kMotorPort = 0;
-static constexpr int kEncoderAChannel = 0;
-static constexpr int kEncoderBChannel = 1;
-static constexpr int kJoystickPort = 0;
+inline constexpr int kMotorPort = 0;
+inline constexpr int kEncoderAChannel = 0;
+inline constexpr int kEncoderBChannel = 1;
+inline constexpr int kJoystickPort = 0;
 
-static constexpr std::string_view kArmPositionKey = "ArmPosition";
-static constexpr std::string_view kArmPKey = "ArmP";
+inline constexpr std::string_view kArmPositionKey = "ArmPosition";
+inline constexpr std::string_view kArmPKey = "ArmP";
 
-static constexpr double kDefaultArmKp = 50.0;
-static constexpr units::degree_t kDefaultArmSetpoint = 75.0_deg;
+inline constexpr double kDefaultArmKp = 50.0;
+inline constexpr units::degree_t kDefaultArmSetpoint = 75.0_deg;
 
-static constexpr units::radian_t kMinAngle = -75.0_deg;
-static constexpr units::radian_t kMaxAngle = 255.0_deg;
+inline constexpr units::radian_t kMinAngle = -75.0_deg;
+inline constexpr units::radian_t kMaxAngle = 255.0_deg;
 
-static constexpr double kArmReduction = 200.0;
-static constexpr units::kilogram_t kArmMass = 8.0_kg;
-static constexpr units::meter_t kArmLength = 30.0_in;
+inline constexpr double kArmReduction = 200.0;
+inline constexpr units::kilogram_t kArmMass = 8.0_kg;
+inline constexpr units::meter_t kArmLength = 30.0_in;
 
 // distance per pulse = (angle per revolution) / (pulses per revolution)
 //  = (2 * PI rads) / (4096 pulses)
-static constexpr double kArmEncoderDistPerPulse =
+inline constexpr double kArmEncoderDistPerPulse =
     2.0 * std::numbers::pi / 4096.0;
diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp
index cc7db7b..9470a7a 100644
--- a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp
@@ -12,8 +12,8 @@
   const double rightOutput = m_rightPIDController.Calculate(
       m_rightEncoder.GetRate(), speeds.right.value());
 
-  m_leftGroup.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
-  m_rightGroup.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);
+  m_leftLeader.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
+  m_rightLeader.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);
 }
 
 void Drivetrain::Drive(units::meters_per_second_t xSpeed,
diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h
index 54b2e26..85bccc7 100644
--- a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.h
@@ -12,7 +12,6 @@
 #include <frc/controller/SimpleMotorFeedforward.h>
 #include <frc/kinematics/DifferentialDriveKinematics.h>
 #include <frc/kinematics/DifferentialDriveOdometry.h>
-#include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <units/angle.h>
 #include <units/angular_velocity.h>
@@ -25,10 +24,13 @@
 class Drivetrain {
  public:
   Drivetrain() {
+    m_leftLeader.AddFollower(m_leftFollower);
+    m_rightLeader.AddFollower(m_rightFollower);
+
     // We need to invert one side of the drivetrain so that positive voltages
     // result in both sides moving forward. Depending on how your robot's
     // gearbox is constructed, you might have to invert the left side instead.
-    m_rightGroup.SetInverted(true);
+    m_rightLeader.SetInverted(true);
 
     m_gyro.Reset();
     // Set the distance per pulse for the drive encoders. We can simply use the
@@ -63,9 +65,6 @@
   frc::PWMSparkMax m_rightLeader{3};
   frc::PWMSparkMax m_rightFollower{4};
 
-  frc::MotorControllerGroup m_leftGroup{m_leftLeader, m_leftFollower};
-  frc::MotorControllerGroup m_rightGroup{m_rightLeader, m_rightFollower};
-
   frc::Encoder m_leftEncoder{0, 1};
   frc::Encoder m_rightEncoder{2, 3};
 
diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp
index 725074a..caba17d 100644
--- a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp
@@ -7,10 +7,13 @@
 #include "ExampleGlobalMeasurementSensor.h"
 
 Drivetrain::Drivetrain() {
+  m_leftLeader.AddFollower(m_leftFollower);
+  m_rightLeader.AddFollower(m_rightFollower);
+
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
-  m_rightGroup.SetInverted(true);
+  m_rightLeader.SetInverted(true);
 
   m_gyro.Reset();
 
@@ -37,8 +40,8 @@
   const double rightOutput = m_rightPIDController.Calculate(
       m_rightEncoder.GetRate(), speeds.right.value());
 
-  m_leftGroup.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
-  m_rightGroup.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);
+  m_leftLeader.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
+  m_rightLeader.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);
 }
 
 void Drivetrain::Drive(units::meters_per_second_t xSpeed,
@@ -110,9 +113,9 @@
   // To update our simulation, we set motor voltage inputs, update the
   // simulation, and write the simulated positions and velocities to our
   // simulated encoder and gyro.
-  m_drivetrainSimulator.SetInputs(units::volt_t{m_leftGroup.Get()} *
+  m_drivetrainSimulator.SetInputs(units::volt_t{m_leftLeader.Get()} *
                                       frc::RobotController::GetInputVoltage(),
-                                  units::volt_t{m_rightGroup.Get()} *
+                                  units::volt_t{m_rightLeader.Get()} *
                                       frc::RobotController::GetInputVoltage());
   m_drivetrainSimulator.Update(20_ms);
 
diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h
index ac4de4c..63a9aea 100644
--- a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h
@@ -21,7 +21,6 @@
 #include <frc/geometry/Quaternion.h>
 #include <frc/geometry/Transform3d.h>
 #include <frc/kinematics/DifferentialDriveKinematics.h>
-#include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <frc/simulation/AnalogGyroSim.h>
 #include <frc/simulation/DifferentialDrivetrainSim.h>
@@ -140,9 +139,6 @@
   frc::PWMSparkMax m_rightLeader{3};
   frc::PWMSparkMax m_rightFollower{4};
 
-  frc::MotorControllerGroup m_leftGroup{m_leftLeader, m_leftFollower};
-  frc::MotorControllerGroup m_rightGroup{m_rightLeader, m_rightFollower};
-
   frc::Encoder m_leftEncoder{0, 1};
   frc::Encoder m_rightEncoder{2, 3};
 
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp
index c7eab48..c4c1661 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp
@@ -37,7 +37,7 @@
 void Robot::AutonomousInit() {
   m_autonomousCommand = m_container.GetAutonomousCommand();
 
-  if (m_autonomousCommand != nullptr) {
+  if (m_autonomousCommand) {
     m_autonomousCommand->Schedule();
   }
 }
@@ -49,9 +49,9 @@
   // teleop starts running. If you want the autonomous to
   // continue until interrupted by another command, remove
   // this line or comment it out.
-  if (m_autonomousCommand != nullptr) {
+  if (m_autonomousCommand) {
     m_autonomousCommand->Cancel();
-    m_autonomousCommand = nullptr;
+    m_autonomousCommand.reset();
   }
 }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
index bcb7e73..37ae1aa 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
@@ -4,6 +4,8 @@
 
 #include "RobotContainer.h"
 
+#include <frc2/command/Commands.h>
+
 #include "commands/DriveDistanceProfiled.h"
 
 RobotContainer::RobotContainer() {
@@ -60,7 +62,7 @@
           .WithTimeout(10_s));
 }
 
-frc2::Command* RobotContainer::GetAutonomousCommand() {
+frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
   // Runs the chosen command in autonomous
-  return nullptr;
+  return frc2::cmd::None();
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp
index db8ba70..84fae4f 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp
@@ -12,16 +12,14 @@
       m_rightLeader{kRightMotor1Port},
       m_rightFollower{kRightMotor2Port},
       m_feedforward{ks, kv, ka} {
+  wpi::SendableRegistry::AddChild(&m_drive, &m_leftLeader);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_rightLeader);
+
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
   m_rightLeader.SetInverted(true);
 
-  // You might need to not do this depending on the specific motor controller
-  // that you are using -- contact the respective vendor's documentation for
-  // more details.
-  m_rightFollower.SetInverted(true);
-
   m_leftFollower.Follow(m_leftLeader);
   m_rightFollower.Follow(m_rightLeader);
 
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h
index 7b7de40..c9ec7e7 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h
@@ -22,26 +22,26 @@
  */
 
 namespace DriveConstants {
-constexpr int kLeftMotor1Port = 0;
-constexpr int kLeftMotor2Port = 1;
-constexpr int kRightMotor1Port = 2;
-constexpr int kRightMotor2Port = 3;
+inline constexpr int kLeftMotor1Port = 0;
+inline constexpr int kLeftMotor2Port = 1;
+inline constexpr int kRightMotor1Port = 2;
+inline constexpr int kRightMotor2Port = 3;
 
 // These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
 // These characterization values MUST be determined either experimentally or
 // theoretically for *your* robot's drive. The SysId tool provides a convenient
 // method for obtaining these values for your robot.
-constexpr auto ks = 1_V;
-constexpr auto kv = 0.8_V * 1_s / 1_m;
-constexpr auto ka = 0.15_V * 1_s * 1_s / 1_m;
+inline constexpr auto ks = 1_V;
+inline constexpr auto kv = 0.8_V * 1_s / 1_m;
+inline constexpr auto ka = 0.15_V * 1_s * 1_s / 1_m;
 
-constexpr double kp = 1;
+inline constexpr double kp = 1;
 
-constexpr auto kMaxSpeed = 3_mps;
-constexpr auto kMaxAcceleration = 3_mps_sq;
+inline constexpr auto kMaxSpeed = 3_mps;
+inline constexpr auto kMaxAcceleration = 3_mps_sq;
 
 }  // namespace DriveConstants
 
 namespace OIConstants {
-constexpr int kDriverControllerPort = 0;
+inline constexpr int kDriverControllerPort = 0;
 }  // namespace OIConstants
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/ExampleSmartMotorController.h b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/ExampleSmartMotorController.h
index 71dc4d4..fe09a15 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/ExampleSmartMotorController.h
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/ExampleSmartMotorController.h
@@ -4,15 +4,13 @@
 
 #pragma once
 
-#include <frc/motorcontrol/MotorController.h>
-
 /**
  * A simplified stub class that simulates the API of a common "smart" motor
  * controller.
  *
  * <p>Has no actual functionality.
  */
-class ExampleSmartMotorController : public frc::MotorController {
+class ExampleSmartMotorController {
  public:
   enum PIDMode { kPosition, kVelocity, kMovementWitchcraft };
 
@@ -68,17 +66,17 @@
    */
   void ResetEncoder() {}
 
-  void Set(double speed) override { m_value = speed; }
+  void Set(double speed) { m_value = speed; }
 
-  double Get() const override { return m_value; }
+  double Get() const { return m_value; }
 
-  void SetInverted(bool isInverted) override {}
+  void SetInverted(bool isInverted) {}
 
-  bool GetInverted() const override { return false; }
+  bool GetInverted() const { return false; }
 
-  void Disable() override {}
+  void Disable() {}
 
-  void StopMotor() override {}
+  void StopMotor() {}
 
  private:
   double m_value = 0.0;
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.h
index a82f2ac..de9c814 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.h
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.h
@@ -4,6 +4,8 @@
 
 #pragma once
 
+#include <optional>
+
 #include <frc/TimedRobot.h>
 #include <frc2/command/Command.h>
 
@@ -24,7 +26,7 @@
  private:
   // Have it null by default so that if testing teleop it
   // doesn't have undefined behavior and potentially crash.
-  frc2::Command* m_autonomousCommand = nullptr;
+  std::optional<frc2::CommandPtr> m_autonomousCommand;
 
   RobotContainer m_container;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/RobotContainer.h
index 4700a70..6bfda58 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/RobotContainer.h
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/RobotContainer.h
@@ -23,7 +23,7 @@
  public:
   RobotContainer();
 
-  frc2::Command* GetAutonomousCommand();
+  frc2::CommandPtr GetAutonomousCommand();
 
  private:
   // The driver's controller
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.h
index 9086353..3dd5f03 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.h
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.h
@@ -83,5 +83,7 @@
   frc::SimpleMotorFeedforward<units::meters> m_feedforward;
 
   // The robot's drive
-  frc::DifferentialDrive m_drive{m_leftLeader, m_rightLeader};
+  frc::DifferentialDrive m_drive{
+      [&](double output) { m_leftLeader.Set(output); },
+      [&](double output) { m_rightLeader.Set(output); }};
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/include/ExampleSmartMotorController.h b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/include/ExampleSmartMotorController.h
index 5d55839..bd48d88 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/include/ExampleSmartMotorController.h
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/include/ExampleSmartMotorController.h
@@ -4,15 +4,13 @@
 
 #pragma once
 
-#include <frc/motorcontrol/MotorController.h>
-
 /**
  * A simplified stub class that simulates the API of a common "smart" motor
  * controller.
  *
  * <p>Has no actual functionality.
  */
-class ExampleSmartMotorController : public frc::MotorController {
+class ExampleSmartMotorController {
  public:
   enum PIDMode { kPosition, kVelocity, kMovementWitchcraft };
 
@@ -68,15 +66,15 @@
    */
   void ResetEncoder() {}
 
-  void Set(double speed) override {}
+  void Set(double speed) {}
 
-  double Get() const override { return 0; }
+  double Get() const { return 0; }
 
-  void SetInverted(bool isInverted) override {}
+  void SetInverted(bool isInverted) {}
 
-  bool GetInverted() const override { return false; }
+  bool GetInverted() const { return false; }
 
-  void Disable() override {}
+  void Disable() {}
 
-  void StopMotor() override {}
+  void StopMotor() {}
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Constants.h
index 7c53018..65d98157 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Constants.h
@@ -25,33 +25,33 @@
 
 namespace Constants {
 
-static constexpr int kMotorPort = 0;
-static constexpr int kEncoderAChannel = 0;
-static constexpr int kEncoderBChannel = 1;
-static constexpr int kJoystickPort = 0;
+inline constexpr int kMotorPort = 0;
+inline constexpr int kEncoderAChannel = 0;
+inline constexpr int kEncoderBChannel = 1;
+inline constexpr int kJoystickPort = 0;
 
-static constexpr double kElevatorKp = 0.75;
-static constexpr double kElevatorKi = 0.0;
-static constexpr double kElevatorKd = 0.0;
+inline constexpr double kElevatorKp = 0.75;
+inline constexpr double kElevatorKi = 0.0;
+inline constexpr double kElevatorKd = 0.0;
 
-static constexpr units::volt_t kElevatorMaxV = 10_V;
-static constexpr units::volt_t kElevatorkS = 0.0_V;
-static constexpr units::volt_t kElevatorkG = 0.62_V;
-static constexpr auto kElevatorkV = 3.9_V / 1_mps;
-static constexpr auto kElevatorkA = 0.06_V / 1_mps_sq;
+inline constexpr units::volt_t kElevatorMaxV = 10_V;
+inline constexpr units::volt_t kElevatorkS = 0.0_V;
+inline constexpr units::volt_t kElevatorkG = 0.62_V;
+inline constexpr auto kElevatorkV = 3.9_V / 1_mps;
+inline constexpr auto kElevatorkA = 0.06_V / 1_mps_sq;
 
-static constexpr double kElevatorGearing = 5.0;
-static constexpr units::meter_t kElevatorDrumRadius = 1_in;
-static constexpr units::kilogram_t kCarriageMass = 12_lb;
+inline constexpr double kElevatorGearing = 5.0;
+inline constexpr units::meter_t kElevatorDrumRadius = 1_in;
+inline constexpr units::kilogram_t kCarriageMass = 12_lb;
 
-static constexpr units::meter_t kSetpoint = 42.875_in;
-static constexpr units::meter_t kLowerSetpoint = 15_in;
-static constexpr units::meter_t kMinElevatorHeight = 0_cm;
-static constexpr units::meter_t kMaxElevatorHeight = 50_in;
+inline constexpr units::meter_t kSetpoint = 42.875_in;
+inline constexpr units::meter_t kLowerSetpoint = 15_in;
+inline constexpr units::meter_t kMinElevatorHeight = 0_cm;
+inline constexpr units::meter_t kMaxElevatorHeight = 50_in;
 
 // distance per pulse = (distance per revolution) / (pulses per revolution)
 //  = (Pi * D) / ppr
-static constexpr double kArmEncoderDistPerPulse =
+inline constexpr double kArmEncoderDistPerPulse =
     2.0 * std::numbers::pi * kElevatorDrumRadius.value() / 4096.0;
 
 }  // namespace Constants
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Constants.h
index 7be706f..1123dc0 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Constants.h
@@ -25,31 +25,31 @@
 
 namespace Constants {
 
-static constexpr int kMotorPort = 0;
-static constexpr int kEncoderAChannel = 0;
-static constexpr int kEncoderBChannel = 1;
-static constexpr int kJoystickPort = 0;
+inline constexpr int kMotorPort = 0;
+inline constexpr int kEncoderAChannel = 0;
+inline constexpr int kEncoderBChannel = 1;
+inline constexpr int kJoystickPort = 0;
 
-static constexpr double kElevatorKp = 5.0;
-static constexpr double kElevatorKi = 0.0;
-static constexpr double kElevatorKd = 0.0;
+inline constexpr double kElevatorKp = 5.0;
+inline constexpr double kElevatorKi = 0.0;
+inline constexpr double kElevatorKd = 0.0;
 
-static constexpr units::volt_t kElevatorkS = 0.0_V;
-static constexpr units::volt_t kElevatorkG = 0.762_V;
-static constexpr auto kElevatorkV = 0.762_V / 1_mps;
-static constexpr auto kElevatorkA = 0.0_V / 1_mps_sq;
+inline constexpr units::volt_t kElevatorkS = 0.0_V;
+inline constexpr units::volt_t kElevatorkG = 0.762_V;
+inline constexpr auto kElevatorkV = 0.762_V / 1_mps;
+inline constexpr auto kElevatorkA = 0.0_V / 1_mps_sq;
 
-static constexpr double kElevatorGearing = 10.0;
-static constexpr units::meter_t kElevatorDrumRadius = 2_in;
-static constexpr units::kilogram_t kCarriageMass = 4.0_kg;
+inline constexpr double kElevatorGearing = 10.0;
+inline constexpr units::meter_t kElevatorDrumRadius = 2_in;
+inline constexpr units::kilogram_t kCarriageMass = 4.0_kg;
 
-static constexpr units::meter_t kSetpoint = 75_cm;
-static constexpr units::meter_t kMinElevatorHeight = 0_cm;
-static constexpr units::meter_t kMaxElevatorHeight = 1.25_m;
+inline constexpr units::meter_t kSetpoint = 75_cm;
+inline constexpr units::meter_t kMinElevatorHeight = 0_cm;
+inline constexpr units::meter_t kMaxElevatorHeight = 1.25_m;
 
 // distance per pulse = (distance per revolution) / (pulses per revolution)
 //  = (Pi * D) / ppr
-static constexpr double kArmEncoderDistPerPulse =
+inline constexpr double kArmEncoderDistPerPulse =
     2.0 * std::numbers::pi * kElevatorDrumRadius.value() / 4096.0;
 
 }  // namespace Constants
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp
index fb3a70d..63cd55d 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp
@@ -34,7 +34,7 @@
 
     // Retrieve the profiled setpoint for the next timestep. This setpoint moves
     // toward the goal while obeying the constraints.
-    m_setpoint = m_profile.Calculate(kDt, m_goal, m_setpoint);
+    m_setpoint = m_profile.Calculate(kDt, m_setpoint, m_goal);
 
     // Send setpoint to offboard controller PID
     m_motor.SetSetpoint(ExampleSmartMotorController::PIDMode::kPosition,
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/include/ExampleSmartMotorController.h b/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/include/ExampleSmartMotorController.h
index 5d55839..bd48d88 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/include/ExampleSmartMotorController.h
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/include/ExampleSmartMotorController.h
@@ -4,15 +4,13 @@
 
 #pragma once
 
-#include <frc/motorcontrol/MotorController.h>
-
 /**
  * A simplified stub class that simulates the API of a common "smart" motor
  * controller.
  *
  * <p>Has no actual functionality.
  */
-class ExampleSmartMotorController : public frc::MotorController {
+class ExampleSmartMotorController {
  public:
   enum PIDMode { kPosition, kVelocity, kMovementWitchcraft };
 
@@ -68,15 +66,15 @@
    */
   void ResetEncoder() {}
 
-  void Set(double speed) override {}
+  void Set(double speed) {}
 
-  double Get() const override { return 0; }
+  double Get() const { return 0; }
 
-  void SetInverted(bool isInverted) override {}
+  void SetInverted(bool isInverted) {}
 
-  bool GetInverted() const override { return false; }
+  bool GetInverted() const { return false; }
 
-  void Disable() override {}
+  void Disable() {}
 
-  void StopMotor() override {}
+  void StopMotor() {}
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/DriveSubsystem.cpp
index f40a649..0e4068f 100644
--- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/DriveSubsystem.cpp
@@ -13,10 +13,16 @@
       m_right2{kRightMotor2Port},
       m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
       m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} {
+  wpi::SendableRegistry::AddChild(&m_drive, &m_left1);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_right1);
+
+  m_left1.AddFollower(m_left2);
+  m_right1.AddFollower(m_right2);
+
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
-  m_leftMotors.SetInverted(true);
+  m_left1.SetInverted(true);
 
   // Set the distance per pulse for the encoders
   m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Constants.h
index 855603a..d3aab41 100644
--- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/Constants.h
@@ -20,56 +20,56 @@
  */
 
 namespace DriveConstants {
-constexpr int kLeftMotor1Port = 0;
-constexpr int kLeftMotor2Port = 1;
-constexpr int kRightMotor1Port = 2;
-constexpr int kRightMotor2Port = 3;
+inline constexpr int kLeftMotor1Port = 0;
+inline constexpr int kLeftMotor2Port = 1;
+inline constexpr int kRightMotor1Port = 2;
+inline constexpr int kRightMotor2Port = 3;
 
-constexpr int kLeftEncoderPorts[]{0, 1};
-constexpr int kRightEncoderPorts[]{2, 3};
-constexpr bool kLeftEncoderReversed = false;
-constexpr bool kRightEncoderReversed = true;
+inline constexpr int kLeftEncoderPorts[]{0, 1};
+inline constexpr int kRightEncoderPorts[]{2, 3};
+inline constexpr bool kLeftEncoderReversed = false;
+inline constexpr bool kRightEncoderReversed = true;
 
-constexpr int kEncoderCPR = 1024;
-constexpr double kWheelDiameterInches = 6;
-constexpr double kEncoderDistancePerPulse =
+inline constexpr int kEncoderCPR = 1024;
+inline constexpr double kWheelDiameterInches = 6;
+inline constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
     (kWheelDiameterInches * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 }  // namespace DriveConstants
 
 namespace ShooterConstants {
-constexpr int kEncoderPorts[]{4, 5};
-constexpr bool kEncoderReversed = false;
-constexpr int kEncoderCPR = 1024;
-constexpr double kEncoderDistancePerPulse =
+inline constexpr int kEncoderPorts[]{4, 5};
+inline constexpr bool kEncoderReversed = false;
+inline constexpr int kEncoderCPR = 1024;
+inline constexpr double kEncoderDistancePerPulse =
     // Distance units will be rotations
     1.0 / static_cast<double>(kEncoderCPR);
 
-constexpr int kShooterMotorPort = 4;
-constexpr int kFeederMotorPort = 5;
+inline constexpr int kShooterMotorPort = 4;
+inline constexpr int kFeederMotorPort = 5;
 
-constexpr auto kShooterFreeRPS = 5300_tr / 1_s;
-constexpr auto kShooterTargetRPS = 4000_tr / 1_s;
-constexpr auto kShooterToleranceRPS = 50_tr / 1_s;
+inline constexpr auto kShooterFreeRPS = 5300_tr / 1_s;
+inline constexpr auto kShooterTargetRPS = 4000_tr / 1_s;
+inline constexpr auto kShooterToleranceRPS = 50_tr / 1_s;
 
-constexpr double kP = 1;
-constexpr double kI = 0;
-constexpr double kD = 0;
+inline constexpr double kP = 1;
+inline constexpr double kI = 0;
+inline constexpr double kD = 0;
 
 // On a real robot the feedforward constants should be empirically determined;
 // these are reasonable guesses.
-constexpr auto kS = 0.05_V;
-constexpr auto kV =
+inline constexpr auto kS = 0.05_V;
+inline constexpr auto kV =
     // Should have value 12V at free speed...
     12_V / kShooterFreeRPS;
 
-constexpr double kFeederSpeed = 0.5;
+inline constexpr double kFeederSpeed = 0.5;
 }  // namespace ShooterConstants
 
 namespace AutoConstants {
-constexpr auto kAutoTimeoutSeconds = 12_s;
-constexpr auto kAutoShootTimeSeconds = 7_s;
+inline constexpr auto kAutoTimeoutSeconds = 12_s;
+inline constexpr auto kAutoShootTimeSeconds = 7_s;
 }  // namespace AutoConstants
 
 namespace OIConstants {
diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/subsystems/DriveSubsystem.h
index 47bf28e..47d3f3d 100644
--- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/subsystems/DriveSubsystem.h
+++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/subsystems/DriveSubsystem.h
@@ -6,7 +6,6 @@
 
 #include <frc/Encoder.h>
 #include <frc/drive/DifferentialDrive.h>
-#include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <frc2/command/SubsystemBase.h>
 
@@ -75,14 +74,9 @@
   frc::PWMSparkMax m_right1;
   frc::PWMSparkMax m_right2;
 
-  // The motors on the left side of the drive
-  frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
-
-  // The motors on the right side of the drive
-  frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
-
   // The robot's drive
-  frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
+  frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); },
+                                 [&](double output) { m_right1.Set(output); }};
 
   // The left-side drive encoder
   frc::Encoder m_leftEncoder;
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp
index 2bfd391..2928036 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp
@@ -11,10 +11,16 @@
 #include <units/length.h>
 
 Drivetrain::Drivetrain() {
+  wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft);
+  wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight);
+
+  m_frontLeft.AddFollower(m_rearLeft);
+  m_frontRight.AddFollower(m_rearRight);
+
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
-  m_right.SetInverted(true);
+  m_frontRight.SetInverted(true);
 
 // Encoders may measure differently in the real world and in
 // simulation. In this example the robot moves 0.042 barleycorns
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Drivetrain.h
index 9e739c4..cc3c95f 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Drivetrain.h
@@ -8,7 +8,6 @@
 #include <frc/AnalogInput.h>
 #include <frc/Encoder.h>
 #include <frc/drive/DifferentialDrive.h>
-#include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <frc2/command/SubsystemBase.h>
 
@@ -66,13 +65,13 @@
  private:
   frc::PWMSparkMax m_frontLeft{1};
   frc::PWMSparkMax m_rearLeft{2};
-  frc::MotorControllerGroup m_left{m_frontLeft, m_rearLeft};
 
   frc::PWMSparkMax m_frontRight{3};
   frc::PWMSparkMax m_rearRight{4};
-  frc::MotorControllerGroup m_right{m_frontRight, m_rearRight};
 
-  frc::DifferentialDrive m_robotDrive{m_left, m_right};
+  frc::DifferentialDrive m_robotDrive{
+      [&](double output) { m_frontLeft.Set(output); },
+      [&](double output) { m_frontRight.Set(output); }};
 
   frc::Encoder m_leftEncoder{1, 2};
   frc::Encoder m_rightEncoder{3, 4};
diff --git a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp
index 01b7210..0a73f14 100644
--- a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp
@@ -11,6 +11,9 @@
 class Robot : public frc::TimedRobot {
  public:
   Robot() {
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_left);
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_right);
+
     // We need to invert one side of the drivetrain so that positive voltages
     // result in both sides moving forward. Depending on how your robot's
     // gearbox is constructed, you might have to invert the left side instead.
@@ -48,7 +51,9 @@
   // Robot drive system
   frc::PWMSparkMax m_left{0};
   frc::PWMSparkMax m_right{1};
-  frc::DifferentialDrive m_robotDrive{m_left, m_right};
+  frc::DifferentialDrive m_robotDrive{
+      [&](double output) { m_left.Set(output); },
+      [&](double output) { m_right.Set(output); }};
 
   frc::XboxController m_controller{0};
   frc::Timer m_timer;
diff --git a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp
index 5230c7c..d8af410 100644
--- a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp
@@ -17,6 +17,11 @@
  */
 class Robot : public frc::TimedRobot {
  public:
+  Robot() {
+    wpi::SendableRegistry::AddChild(&m_drive, &m_left);
+    wpi::SendableRegistry::AddChild(&m_drive, &m_right);
+  }
+
   void RobotInit() override {
     m_gyro.SetSensitivity(kVoltsPerDegreePerSecond);
     // We need to invert one side of the drivetrain so that positive voltages
@@ -50,7 +55,8 @@
 
   frc::PWMSparkMax m_left{kLeftMotorPort};
   frc::PWMSparkMax m_right{kRightMotorPort};
-  frc::DifferentialDrive m_drive{m_left, m_right};
+  frc::DifferentialDrive m_drive{[&](double output) { m_left.Set(output); },
+                                 [&](double output) { m_right.Set(output); }};
 
   frc::AnalogGyro m_gyro{kGyroPort};
   frc::Joystick m_joystick{kJoystickPort};
diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/Robot.cpp
index c7eab48..c4c1661 100644
--- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/Robot.cpp
@@ -37,7 +37,7 @@
 void Robot::AutonomousInit() {
   m_autonomousCommand = m_container.GetAutonomousCommand();
 
-  if (m_autonomousCommand != nullptr) {
+  if (m_autonomousCommand) {
     m_autonomousCommand->Schedule();
   }
 }
@@ -49,9 +49,9 @@
   // teleop starts running. If you want the autonomous to
   // continue until interrupted by another command, remove
   // this line or comment it out.
-  if (m_autonomousCommand != nullptr) {
+  if (m_autonomousCommand) {
     m_autonomousCommand->Cancel();
-    m_autonomousCommand = nullptr;
+    m_autonomousCommand.reset();
   }
 }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp
index 50b9900..7b07684 100644
--- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp
@@ -64,7 +64,7 @@
       .OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }, {}));
 }
 
-frc2::Command* RobotContainer::GetAutonomousCommand() {
+frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
   // no auto
-  return nullptr;
+  return frc2::cmd::None();
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp
index 0cbd0e5..a97a5c0 100644
--- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/subsystems/DriveSubsystem.cpp
@@ -13,10 +13,16 @@
       m_right2{kRightMotor2Port},
       m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
       m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} {
+  wpi::SendableRegistry::AddChild(&m_drive, &m_left1);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_right1);
+
+  m_left1.AddFollower(m_left2);
+  m_right1.AddFollower(m_right2);
+
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
-  m_rightMotors.SetInverted(true);
+  m_right1.SetInverted(true);
 
   // Set the distance per pulse for the encoders
   m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Constants.h
index 77673c9..4d25b0b 100644
--- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Constants.h
@@ -19,46 +19,46 @@
  */
 
 namespace DriveConstants {
-constexpr int kLeftMotor1Port = 0;
-constexpr int kLeftMotor2Port = 1;
-constexpr int kRightMotor1Port = 2;
-constexpr int kRightMotor2Port = 3;
+inline constexpr int kLeftMotor1Port = 0;
+inline constexpr int kLeftMotor2Port = 1;
+inline constexpr int kRightMotor1Port = 2;
+inline constexpr int kRightMotor2Port = 3;
 
-constexpr int kLeftEncoderPorts[]{0, 1};
-constexpr int kRightEncoderPorts[]{2, 3};
-constexpr bool kLeftEncoderReversed = false;
-constexpr bool kRightEncoderReversed = true;
+inline constexpr int kLeftEncoderPorts[]{0, 1};
+inline constexpr int kRightEncoderPorts[]{2, 3};
+inline constexpr bool kLeftEncoderReversed = false;
+inline constexpr bool kRightEncoderReversed = true;
 
-constexpr int kEncoderCPR = 1024;
-constexpr double kWheelDiameterInches = 6;
-constexpr double kEncoderDistancePerPulse =
+inline constexpr int kEncoderCPR = 1024;
+inline constexpr double kWheelDiameterInches = 6;
+inline constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
     (kWheelDiameterInches * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 
-constexpr bool kGyroReversed = true;
+inline constexpr bool kGyroReversed = true;
 
-constexpr double kStabilizationP = 1;
-constexpr double kStabilizationI = 0.5;
-constexpr double kStabilizationD = 0;
+inline constexpr double kStabilizationP = 1;
+inline constexpr double kStabilizationI = 0.5;
+inline constexpr double kStabilizationD = 0;
 
-constexpr double kTurnP = 1;
-constexpr double kTurnI = 0;
-constexpr double kTurnD = 0;
+inline constexpr double kTurnP = 1;
+inline constexpr double kTurnI = 0;
+inline constexpr double kTurnD = 0;
 
-constexpr auto kTurnTolerance = 5_deg;
-constexpr auto kTurnRateTolerance = 10_deg_per_s;
+inline constexpr auto kTurnTolerance = 5_deg;
+inline constexpr auto kTurnRateTolerance = 10_deg_per_s;
 
-constexpr auto kMaxTurnRate = 100_deg_per_s;
-constexpr auto kMaxTurnAcceleration = 300_deg_per_s / 1_s;
+inline constexpr auto kMaxTurnRate = 100_deg_per_s;
+inline constexpr auto kMaxTurnAcceleration = 300_deg_per_s / 1_s;
 }  // namespace DriveConstants
 
 namespace AutoConstants {
-constexpr double kAutoDriveDistanceInches = 60;
-constexpr double kAutoBackupDistanceInches = 20;
-constexpr double kAutoDriveSpeed = 0.5;
+inline constexpr double kAutoDriveDistanceInches = 60;
+inline constexpr double kAutoBackupDistanceInches = 20;
+inline constexpr double kAutoDriveSpeed = 0.5;
 }  // namespace AutoConstants
 
 namespace OIConstants {
-constexpr int kDriverControllerPort = 0;
+inline constexpr int kDriverControllerPort = 0;
 }  // namespace OIConstants
diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Robot.h
index a82f2ac..de9c814 100644
--- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Robot.h
+++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/Robot.h
@@ -4,6 +4,8 @@
 
 #pragma once
 
+#include <optional>
+
 #include <frc/TimedRobot.h>
 #include <frc2/command/Command.h>
 
@@ -24,7 +26,7 @@
  private:
   // Have it null by default so that if testing teleop it
   // doesn't have undefined behavior and potentially crash.
-  frc2::Command* m_autonomousCommand = nullptr;
+  std::optional<frc2::CommandPtr> m_autonomousCommand;
 
   RobotContainer m_container;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/RobotContainer.h
index 041812e..0ecb728 100644
--- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/RobotContainer.h
+++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/RobotContainer.h
@@ -8,6 +8,7 @@
 #include <frc/controller/PIDController.h>
 #include <frc/smartdashboard/SendableChooser.h>
 #include <frc2/command/Command.h>
+#include <frc2/command/CommandPtr.h>
 #include <frc2/command/InstantCommand.h>
 
 #include "Constants.h"
@@ -28,7 +29,7 @@
  public:
   RobotContainer();
 
-  frc2::Command* GetAutonomousCommand();
+  frc2::CommandPtr GetAutonomousCommand();
 
  private:
   // The driver's controller
@@ -39,8 +40,5 @@
   // The robot's subsystems
   DriveSubsystem m_drive;
 
-  // The chooser for the autonomous routines
-  frc::SendableChooser<frc2::Command*> m_chooser;
-
   void ConfigureButtonBindings();
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/subsystems/DriveSubsystem.h
index 96174dd..d7cce6c 100644
--- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/subsystems/DriveSubsystem.h
+++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/subsystems/DriveSubsystem.h
@@ -7,7 +7,6 @@
 #include <frc/ADXRS450_Gyro.h>
 #include <frc/Encoder.h>
 #include <frc/drive/DifferentialDrive.h>
-#include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <frc2/command/SubsystemBase.h>
 #include <units/angle.h>
@@ -91,14 +90,9 @@
   frc::PWMSparkMax m_right1;
   frc::PWMSparkMax m_right2;
 
-  // The motors on the left side of the drive
-  frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
-
-  // The motors on the right side of the drive
-  frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
-
   // The robot's drive
-  frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
+  frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); },
+                                 [&](double output) { m_right1.Set(output); }};
 
   // The left-side drive encoder
   frc::Encoder m_leftEncoder;
diff --git a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp
index 2207f79..7c589fd 100644
--- a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp
@@ -16,6 +16,11 @@
 class Robot : public frc::TimedRobot {
  public:
   void RobotInit() override {
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft);
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearLeft);
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight);
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearRight);
+
     // Invert the right side motors. You may need to change or remove this to
     // match your robot.
     m_frontRight.SetInverted(true);
@@ -48,8 +53,11 @@
   frc::PWMSparkMax m_rearLeft{kRearLeftMotorPort};
   frc::PWMSparkMax m_frontRight{kFrontRightMotorPort};
   frc::PWMSparkMax m_rearRight{kRearRightMotorPort};
-  frc::MecanumDrive m_robotDrive{m_frontLeft, m_rearLeft, m_frontRight,
-                                 m_rearRight};
+  frc::MecanumDrive m_robotDrive{
+      [&](double output) { m_frontLeft.Set(output); },
+      [&](double output) { m_rearLeft.Set(output); },
+      [&](double output) { m_frontRight.Set(output); },
+      [&](double output) { m_rearRight.Set(output); }};
 
   frc::AnalogGyro m_gyro{kGyroPort};
   frc::Joystick m_joystick{kJoystickPort};
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp
index 3372a4d..d7b33ea 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp
@@ -15,10 +15,16 @@
       m_right2{kRightMotor2Port},
       m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
       m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} {
+  wpi::SendableRegistry::AddChild(&m_drive, &m_left1);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_right1);
+
+  m_left1.AddFollower(m_left2);
+  m_right1.AddFollower(m_right2);
+
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
-  m_rightMotors.SetInverted(true);
+  m_right1.SetInverted(true);
 
   // Set the distance per pulse for the encoders
   m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Constants.h
index 7a2bdae..f82b8db 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Constants.h
@@ -16,35 +16,35 @@
  */
 
 namespace DriveConstants {
-constexpr int kLeftMotor1Port = 0;
-constexpr int kLeftMotor2Port = 1;
-constexpr int kRightMotor1Port = 2;
-constexpr int kRightMotor2Port = 3;
+inline constexpr int kLeftMotor1Port = 0;
+inline constexpr int kLeftMotor2Port = 1;
+inline constexpr int kRightMotor1Port = 2;
+inline constexpr int kRightMotor2Port = 3;
 
-constexpr int kLeftEncoderPorts[]{0, 1};
-constexpr int kRightEncoderPorts[]{2, 3};
-constexpr bool kLeftEncoderReversed = false;
-constexpr bool kRightEncoderReversed = true;
+inline constexpr int kLeftEncoderPorts[]{0, 1};
+inline constexpr int kRightEncoderPorts[]{2, 3};
+inline constexpr bool kLeftEncoderReversed = false;
+inline constexpr bool kRightEncoderReversed = true;
 
-constexpr int kEncoderCPR = 1024;
-constexpr double kWheelDiameterInches = 6;
-constexpr double kEncoderDistancePerPulse =
+inline constexpr int kEncoderCPR = 1024;
+inline constexpr double kWheelDiameterInches = 6;
+inline constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
     (kWheelDiameterInches * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 }  // namespace DriveConstants
 
 namespace HatchConstants {
-constexpr int kHatchSolenoidModule = 0;
-constexpr int kHatchSolenoidPorts[]{0, 1};
+inline constexpr int kHatchSolenoidModule = 0;
+inline constexpr int kHatchSolenoidPorts[]{0, 1};
 }  // namespace HatchConstants
 
 namespace AutoConstants {
-constexpr double kAutoDriveDistanceInches = 60;
-constexpr double kAutoBackupDistanceInches = 20;
-constexpr double kAutoDriveSpeed = 0.5;
+inline constexpr double kAutoDriveDistanceInches = 60;
+inline constexpr double kAutoBackupDistanceInches = 20;
+inline constexpr double kAutoDriveSpeed = 0.5;
 }  // namespace AutoConstants
 
 namespace OIConstants {
-constexpr int kDriverControllerPort = 0;
+inline constexpr int kDriverControllerPort = 0;
 }  // namespace OIConstants
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.h
index 5984a1a..6cab580 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.h
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.h
@@ -6,7 +6,6 @@
 
 #include <frc/Encoder.h>
 #include <frc/drive/DifferentialDrive.h>
-#include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <frc2/command/SubsystemBase.h>
 
@@ -63,14 +62,9 @@
   frc::PWMSparkMax m_right1;
   frc::PWMSparkMax m_right2;
 
-  // The motors on the left side of the drive
-  frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
-
-  // The motors on the right side of the drive
-  frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
-
   // The robot's drive
-  frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
+  frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); },
+                                 [&](double output) { m_right1.Set(output); }};
 
   // The left-side drive encoder
   frc::Encoder m_leftEncoder;
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp
index 3372a4d..d7b33ea 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp
@@ -15,10 +15,16 @@
       m_right2{kRightMotor2Port},
       m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
       m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} {
+  wpi::SendableRegistry::AddChild(&m_drive, &m_left1);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_right1);
+
+  m_left1.AddFollower(m_left2);
+  m_right1.AddFollower(m_right2);
+
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
-  m_rightMotors.SetInverted(true);
+  m_right1.SetInverted(true);
 
   // Set the distance per pulse for the encoders
   m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Constants.h
index 7a2bdae..534d8f1 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Constants.h
@@ -16,27 +16,27 @@
  */
 
 namespace DriveConstants {
-constexpr int kLeftMotor1Port = 0;
-constexpr int kLeftMotor2Port = 1;
-constexpr int kRightMotor1Port = 2;
-constexpr int kRightMotor2Port = 3;
+inline constexpr int kLeftMotor1Port = 0;
+inline constexpr int kLeftMotor2Port = 1;
+inline constexpr int kRightMotor1Port = 2;
+inline constexpr int kRightMotor2Port = 3;
 
-constexpr int kLeftEncoderPorts[]{0, 1};
-constexpr int kRightEncoderPorts[]{2, 3};
-constexpr bool kLeftEncoderReversed = false;
-constexpr bool kRightEncoderReversed = true;
+inline constexpr int kLeftEncoderPorts[]{0, 1};
+inline constexpr int kRightEncoderPorts[]{2, 3};
+inline constexpr bool kLeftEncoderReversed = false;
+inline constexpr bool kRightEncoderReversed = true;
 
-constexpr int kEncoderCPR = 1024;
-constexpr double kWheelDiameterInches = 6;
-constexpr double kEncoderDistancePerPulse =
+inline constexpr int kEncoderCPR = 1024;
+inline constexpr double kWheelDiameterInches = 6;
+inline constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
     (kWheelDiameterInches * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 }  // namespace DriveConstants
 
 namespace HatchConstants {
-constexpr int kHatchSolenoidModule = 0;
-constexpr int kHatchSolenoidPorts[]{0, 1};
+inline constexpr int kHatchSolenoidModule = 0;
+inline constexpr int kHatchSolenoidPorts[]{0, 1};
 }  // namespace HatchConstants
 
 namespace AutoConstants {
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.h
index 5984a1a..6cab580 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.h
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.h
@@ -6,7 +6,6 @@
 
 #include <frc/Encoder.h>
 #include <frc/drive/DifferentialDrive.h>
-#include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <frc2/command/SubsystemBase.h>
 
@@ -63,14 +62,9 @@
   frc::PWMSparkMax m_right1;
   frc::PWMSparkMax m_right2;
 
-  // The motors on the left side of the drive
-  frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
-
-  // The motors on the right side of the drive
-  frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
-
   // The robot's drive
-  frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
+  frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); },
+                                 [&](double output) { m_right1.Set(output); }};
 
   // The left-side drive encoder
   frc::Encoder m_leftEncoder;
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Robot.cpp
index c7eab48..c4c1661 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Robot.cpp
@@ -37,7 +37,7 @@
 void Robot::AutonomousInit() {
   m_autonomousCommand = m_container.GetAutonomousCommand();
 
-  if (m_autonomousCommand != nullptr) {
+  if (m_autonomousCommand) {
     m_autonomousCommand->Schedule();
   }
 }
@@ -49,9 +49,9 @@
   // teleop starts running. If you want the autonomous to
   // continue until interrupted by another command, remove
   // this line or comment it out.
-  if (m_autonomousCommand != nullptr) {
+  if (m_autonomousCommand) {
     m_autonomousCommand->Cancel();
-    m_autonomousCommand = nullptr;
+    m_autonomousCommand.reset();
   }
 }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp
index 0f691e0..856ec99 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/RobotContainer.cpp
@@ -12,6 +12,7 @@
 #include <frc/trajectory/Trajectory.h>
 #include <frc/trajectory/TrajectoryGenerator.h>
 #include <frc/trajectory/constraint/MecanumDriveKinematicsConstraint.h>
+#include <frc2/command/Commands.h>
 #include <frc2/command/InstantCommand.h>
 #include <frc2/command/MecanumControllerCommand.h>
 #include <frc2/command/SequentialCommandGroup.h>
@@ -47,7 +48,7 @@
       .OnFalse(&m_driveFullSpeed);
 }
 
-frc2::Command* RobotContainer::GetAutonomousCommand() {
+frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
   // Set up config for trajectory
   frc::TrajectoryConfig config(AutoConstants::kMaxSpeed,
                                AutoConstants::kMaxAcceleration);
@@ -65,48 +66,57 @@
       // Pass the config
       config);
 
-  frc2::MecanumControllerCommand mecanumControllerCommand(
-      exampleTrajectory, [this]() { return m_drive.GetPose(); },
+  frc2::CommandPtr mecanumControllerCommand =
+      frc2::MecanumControllerCommand(
+          exampleTrajectory, [this]() { return m_drive.GetPose(); },
 
-      frc::SimpleMotorFeedforward<units::meters>(ks, kv, ka),
-      DriveConstants::kDriveKinematics,
+          frc::SimpleMotorFeedforward<units::meters>(ks, kv, ka),
+          DriveConstants::kDriveKinematics,
 
-      frc::PIDController{AutoConstants::kPXController, 0, 0},
-      frc::PIDController{AutoConstants::kPYController, 0, 0},
-      frc::ProfiledPIDController<units::radians>(
-          AutoConstants::kPThetaController, 0, 0,
-          AutoConstants::kThetaControllerConstraints),
+          frc::PIDController{AutoConstants::kPXController, 0, 0},
+          frc::PIDController{AutoConstants::kPYController, 0, 0},
+          frc::ProfiledPIDController<units::radians>(
+              AutoConstants::kPThetaController, 0, 0,
+              AutoConstants::kThetaControllerConstraints),
 
-      AutoConstants::kMaxSpeed,
+          AutoConstants::kMaxSpeed,
 
-      [this]() {
-        return frc::MecanumDriveWheelSpeeds{
-            units::meters_per_second_t{m_drive.GetFrontLeftEncoder().GetRate()},
-            units::meters_per_second_t{
-                m_drive.GetFrontRightEncoder().GetRate()},
-            units::meters_per_second_t{m_drive.GetRearLeftEncoder().GetRate()},
-            units::meters_per_second_t{
-                m_drive.GetRearRightEncoder().GetRate()}};
-      },
+          [this]() {
+            return frc::MecanumDriveWheelSpeeds{
+                units::meters_per_second_t{
+                    m_drive.GetFrontLeftEncoder().GetRate()},
+                units::meters_per_second_t{
+                    m_drive.GetFrontRightEncoder().GetRate()},
+                units::meters_per_second_t{
+                    m_drive.GetRearLeftEncoder().GetRate()},
+                units::meters_per_second_t{
+                    m_drive.GetRearRightEncoder().GetRate()}};
+          },
 
-      frc::PIDController{DriveConstants::kPFrontLeftVel, 0, 0},
-      frc::PIDController{DriveConstants::kPRearLeftVel, 0, 0},
-      frc::PIDController{DriveConstants::kPFrontRightVel, 0, 0},
-      frc::PIDController{DriveConstants::kPRearRightVel, 0, 0},
+          frc::PIDController{DriveConstants::kPFrontLeftVel, 0, 0},
+          frc::PIDController{DriveConstants::kPRearLeftVel, 0, 0},
+          frc::PIDController{DriveConstants::kPFrontRightVel, 0, 0},
+          frc::PIDController{DriveConstants::kPRearRightVel, 0, 0},
 
-      [this](units::volt_t frontLeft, units::volt_t rearLeft,
-             units::volt_t frontRight, units::volt_t rearRight) {
-        m_drive.SetMotorControllersVolts(frontLeft, rearLeft, frontRight,
-                                         rearRight);
-      },
+          [this](units::volt_t frontLeft, units::volt_t rearLeft,
+                 units::volt_t frontRight, units::volt_t rearRight) {
+            m_drive.SetMotorControllersVolts(frontLeft, rearLeft, frontRight,
+                                             rearRight);
+          },
 
-      {&m_drive});
+          {&m_drive})
+          .ToPtr();
 
-  // Reset odometry to the starting pose of the trajectory.
-  m_drive.ResetOdometry(exampleTrajectory.InitialPose());
-
-  // no auto
-  return new frc2::SequentialCommandGroup(
+  // Reset odometry to the initial pose of the trajectory, run path following
+  // command, then stop at the end.
+  return frc2::cmd::Sequence(
+      frc2::InstantCommand(
+          [this, &exampleTrajectory]() {
+            m_drive.ResetOdometry(exampleTrajectory.InitialPose());
+          },
+          {})
+          .ToPtr(),
       std::move(mecanumControllerCommand),
-      frc2::InstantCommand([this]() { m_drive.Drive(0, 0, 0, false); }, {}));
+      frc2::InstantCommand([this]() { m_drive.Drive(0, 0, 0, false); }, {})
+          .ToPtr());
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/subsystems/DriveSubsystem.cpp
index 292ad1f..8a55821 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/subsystems/DriveSubsystem.cpp
@@ -30,6 +30,11 @@
 
       m_odometry{kDriveKinematics, m_gyro.GetRotation2d(),
                  getCurrentWheelDistances(), frc::Pose2d{}} {
+  wpi::SendableRegistry::AddChild(&m_drive, &m_frontLeft);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_rearLeft);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_frontRight);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_rearRight);
+
   // Set the distance per pulse for the encoders
   m_frontLeftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
   m_rearLeftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h
index 527504a..7dde79c 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h
@@ -28,30 +28,30 @@
  */
 
 namespace DriveConstants {
-constexpr int kFrontLeftMotorPort = 0;
-constexpr int kRearLeftMotorPort = 1;
-constexpr int kFrontRightMotorPort = 2;
-constexpr int kRearRightMotorPort = 3;
+inline constexpr int kFrontLeftMotorPort = 0;
+inline constexpr int kRearLeftMotorPort = 1;
+inline constexpr int kFrontRightMotorPort = 2;
+inline constexpr int kRearRightMotorPort = 3;
 
-constexpr int kFrontLeftEncoderPorts[]{0, 1};
-constexpr int kRearLeftEncoderPorts[]{2, 3};
-constexpr int kFrontRightEncoderPorts[]{4, 5};
-constexpr int kRearRightEncoderPorts[]{6, 7};
+inline constexpr int kFrontLeftEncoderPorts[]{0, 1};
+inline constexpr int kRearLeftEncoderPorts[]{2, 3};
+inline constexpr int kFrontRightEncoderPorts[]{4, 5};
+inline constexpr int kRearRightEncoderPorts[]{6, 7};
 
-constexpr bool kFrontLeftEncoderReversed = false;
-constexpr bool kRearLeftEncoderReversed = true;
-constexpr bool kFrontRightEncoderReversed = false;
-constexpr bool kRearRightEncoderReversed = true;
+inline constexpr bool kFrontLeftEncoderReversed = false;
+inline constexpr bool kRearLeftEncoderReversed = true;
+inline constexpr bool kFrontRightEncoderReversed = false;
+inline constexpr bool kRearRightEncoderReversed = true;
 
-constexpr auto kTrackWidth =
+inline constexpr auto kTrackWidth =
     0.5_m;  // Distance between centers of right and left wheels on robot
-constexpr auto kWheelBase =
+inline constexpr auto kWheelBase =
     0.7_m;  // Distance between centers of front and back wheels on robot
 extern const frc::MecanumDriveKinematics kDriveKinematics;
 
-constexpr int kEncoderCPR = 1024;
-constexpr double kWheelDiameterMeters = 0.15;
-constexpr double kEncoderDistancePerPulse =
+inline constexpr int kEncoderCPR = 1024;
+inline constexpr double kWheelDiameterMeters = 0.15;
+inline constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
     (kWheelDiameterMeters * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
@@ -60,26 +60,26 @@
 // These characterization values MUST be determined either experimentally or
 // theoretically for *your* robot's drive. The SysId tool provides a convenient
 // method for obtaining these values for your robot.
-constexpr auto ks = 1_V;
-constexpr auto kv = 0.8 * 1_V * 1_s / 1_m;
-constexpr auto ka = 0.15 * 1_V * 1_s * 1_s / 1_m;
+inline constexpr auto ks = 1_V;
+inline constexpr auto kv = 0.8 * 1_V * 1_s / 1_m;
+inline constexpr auto ka = 0.15 * 1_V * 1_s * 1_s / 1_m;
 
 // Example value only - as above, this must be tuned for your drive!
-constexpr double kPFrontLeftVel = 0.5;
-constexpr double kPRearLeftVel = 0.5;
-constexpr double kPFrontRightVel = 0.5;
-constexpr double kPRearRightVel = 0.5;
+inline constexpr double kPFrontLeftVel = 0.5;
+inline constexpr double kPRearLeftVel = 0.5;
+inline constexpr double kPFrontRightVel = 0.5;
+inline constexpr double kPRearRightVel = 0.5;
 }  // namespace DriveConstants
 
 namespace AutoConstants {
-constexpr auto kMaxSpeed = 3_mps;
-constexpr auto kMaxAcceleration = 3_mps_sq;
-constexpr auto kMaxAngularSpeed = 3_rad_per_s;
-constexpr auto kMaxAngularAcceleration = 3_rad_per_s_sq;
+inline constexpr auto kMaxSpeed = 3_mps;
+inline constexpr auto kMaxAcceleration = 3_mps_sq;
+inline constexpr auto kMaxAngularSpeed = 3_rad_per_s;
+inline constexpr auto kMaxAngularAcceleration = 3_rad_per_s_sq;
 
-constexpr double kPXController = 0.5;
-constexpr double kPYController = 0.5;
-constexpr double kPThetaController = 0.5;
+inline constexpr double kPXController = 0.5;
+inline constexpr double kPYController = 0.5;
+inline constexpr double kPThetaController = 0.5;
 
 extern const frc::TrapezoidProfile<units::radians>::Constraints
     kThetaControllerConstraints;
@@ -87,5 +87,5 @@
 }  // namespace AutoConstants
 
 namespace OIConstants {
-constexpr int kDriverControllerPort = 0;
+inline constexpr int kDriverControllerPort = 0;
 }  // namespace OIConstants
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Robot.h
index a82f2ac..de9c814 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Robot.h
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Robot.h
@@ -4,6 +4,8 @@
 
 #pragma once
 
+#include <optional>
+
 #include <frc/TimedRobot.h>
 #include <frc2/command/Command.h>
 
@@ -24,7 +26,7 @@
  private:
   // Have it null by default so that if testing teleop it
   // doesn't have undefined behavior and potentially crash.
-  frc2::Command* m_autonomousCommand = nullptr;
+  std::optional<frc2::CommandPtr> m_autonomousCommand;
 
   RobotContainer m_container;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/RobotContainer.h
index 93485e3..c6f8afc 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/RobotContainer.h
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/RobotContainer.h
@@ -9,6 +9,7 @@
 #include <frc/controller/ProfiledPIDController.h>
 #include <frc/smartdashboard/SendableChooser.h>
 #include <frc2/command/Command.h>
+#include <frc2/command/CommandPtr.h>
 #include <frc2/command/InstantCommand.h>
 #include <frc2/command/PIDCommand.h>
 #include <frc2/command/ParallelRaceGroup.h>
@@ -28,7 +29,7 @@
  public:
   RobotContainer();
 
-  frc2::Command* GetAutonomousCommand();
+  frc2::CommandPtr GetAutonomousCommand();
 
  private:
   // The driver's controller
@@ -44,8 +45,5 @@
   frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
                                         {}};
 
-  // The chooser for the autonomous routines
-  frc::SendableChooser<frc2::Command*> m_chooser;
-
   void ConfigureButtonBindings();
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h
index 579a395..7efb225 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h
@@ -148,7 +148,10 @@
   frc::PWMSparkMax m_rearRight;
 
   // The robot's drive
-  frc::MecanumDrive m_drive{m_frontLeft, m_rearLeft, m_frontRight, m_rearRight};
+  frc::MecanumDrive m_drive{[&](double output) { m_frontLeft.Set(output); },
+                            [&](double output) { m_rearLeft.Set(output); },
+                            [&](double output) { m_frontRight.Set(output); },
+                            [&](double output) { m_rearRight.Set(output); }};
 
   // The front-left-side drive encoder
   frc::Encoder m_frontLeftEncoder;
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp
index 8d9d7ae..eeb9ce1 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp
@@ -14,6 +14,11 @@
 class Robot : public frc::TimedRobot {
  public:
   void RobotInit() override {
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft);
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearLeft);
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight);
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearRight);
+
     // Invert the right side motors. You may need to change or remove this to
     // match your robot.
     m_frontRight.SetInverted(true);
@@ -40,8 +45,11 @@
   frc::PWMSparkMax m_rearLeft{kRearLeftChannel};
   frc::PWMSparkMax m_frontRight{kFrontRightChannel};
   frc::PWMSparkMax m_rearRight{kRearRightChannel};
-  frc::MecanumDrive m_robotDrive{m_frontLeft, m_rearLeft, m_frontRight,
-                                 m_rearRight};
+  frc::MecanumDrive m_robotDrive{
+      [&](double output) { m_frontLeft.Set(output); },
+      [&](double output) { m_rearLeft.Set(output); },
+      [&](double output) { m_frontRight.Set(output); },
+      [&](double output) { m_rearRight.Set(output); }};
 
   frc::Joystick m_stick{kJoystickChannel};
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp
index 9f1b12b..3e5326c 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp
@@ -50,7 +50,8 @@
                        units::second_t period) {
   auto wheelSpeeds = m_kinematics.ToWheelSpeeds(frc::ChassisSpeeds::Discretize(
       fieldRelative ? frc::ChassisSpeeds::FromFieldRelativeSpeeds(
-                          xSpeed, ySpeed, rot, m_gyro.GetRotation2d())
+                          xSpeed, ySpeed, rot,
+                          m_poseEstimator.GetEstimatedPosition().Rotation())
                     : frc::ChassisSpeeds{xSpeed, ySpeed, rot},
       period));
   wheelSpeeds.Desaturate(kMaxSpeed);
diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp
index e880af2..5fa8c62 100644
--- a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp
@@ -81,10 +81,14 @@
       [this](auto left, auto right) { m_drive.TankDriveVolts(left, right); },
       {&m_drive})};
 
-  // Reset odometry to the starting pose of the trajectory.
-  m_drive.ResetOdometry(exampleTrajectory.InitialPose());
-
-  return std::move(ramseteCommand)
-      .BeforeStarting(
+  // Reset odometry to the initial pose of the trajectory, run path following
+  // command, then stop at the end.
+  return frc2::cmd::RunOnce(
+             [this, &exampleTrajectory] {
+               m_drive.ResetOdometry(exampleTrajectory.InitialPose());
+             },
+             {})
+      .AndThen(std::move(ramseteCommand))
+      .AndThen(
           frc2::cmd::RunOnce([this] { m_drive.TankDriveVolts(0_V, 0_V); }, {}));
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp
index 0bc598e..13e8306 100644
--- a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp
@@ -17,10 +17,16 @@
       m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
       m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]},
       m_odometry{m_gyro.GetRotation2d(), units::meter_t{0}, units::meter_t{0}} {
+  wpi::SendableRegistry::AddChild(&m_drive, &m_left1);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_right1);
+
+  m_left1.AddFollower(m_left2);
+  m_right1.AddFollower(m_right2);
+
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
-  m_rightMotors.SetInverted(true);
+  m_right1.SetInverted(true);
 
   // Set the distance per pulse for the encoders
   m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse.value());
@@ -41,8 +47,8 @@
 }
 
 void DriveSubsystem::TankDriveVolts(units::volt_t left, units::volt_t right) {
-  m_leftMotors.SetVoltage(left);
-  m_rightMotors.SetVoltage(right);
+  m_left1.SetVoltage(left);
+  m_right1.SetVoltage(right);
   m_drive.Feed();
 }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h
index f7a061a..d2ca25b 100644
--- a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h
@@ -25,22 +25,22 @@
  */
 
 namespace DriveConstants {
-constexpr int kLeftMotor1Port = 0;
-constexpr int kLeftMotor2Port = 1;
-constexpr int kRightMotor1Port = 2;
-constexpr int kRightMotor2Port = 3;
+inline constexpr int kLeftMotor1Port = 0;
+inline constexpr int kLeftMotor2Port = 1;
+inline constexpr int kRightMotor1Port = 2;
+inline constexpr int kRightMotor2Port = 3;
 
-constexpr int kLeftEncoderPorts[]{0, 1};
-constexpr int kRightEncoderPorts[]{2, 3};
-constexpr bool kLeftEncoderReversed = false;
-constexpr bool kRightEncoderReversed = true;
+inline constexpr int kLeftEncoderPorts[]{0, 1};
+inline constexpr int kRightEncoderPorts[]{2, 3};
+inline constexpr bool kLeftEncoderReversed = false;
+inline constexpr bool kRightEncoderReversed = true;
 
-constexpr auto kTrackwidth = 0.69_m;
+inline constexpr auto kTrackwidth = 0.69_m;
 extern const frc::DifferentialDriveKinematics kDriveKinematics;
 
-constexpr int kEncoderCPR = 1024;
-constexpr units::meter_t kWheelDiameter = 6_in;
-constexpr auto kEncoderDistancePerPulse =
+inline constexpr int kEncoderCPR = 1024;
+inline constexpr units::meter_t kWheelDiameter = 6_in;
+inline constexpr auto kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
     (kWheelDiameter * std::numbers::pi) / static_cast<double>(kEncoderCPR);
 
@@ -49,24 +49,24 @@
 // theoretically for *your* robot's drive. The Robot Characterization
 // Toolsuite provides a convenient tool for obtaining these values for your
 // robot.
-constexpr auto ks = 0.22_V;
-constexpr auto kv = 1.98 * 1_V * 1_s / 1_m;
-constexpr auto ka = 0.2 * 1_V * 1_s * 1_s / 1_m;
+inline constexpr auto ks = 0.22_V;
+inline constexpr auto kv = 1.98 * 1_V * 1_s / 1_m;
+inline constexpr auto ka = 0.2 * 1_V * 1_s * 1_s / 1_m;
 
 // Example value only - as above, this must be tuned for your drive!
-constexpr double kPDriveVel = 8.5;
+inline constexpr double kPDriveVel = 8.5;
 }  // namespace DriveConstants
 
 namespace AutoConstants {
-constexpr auto kMaxSpeed = 3_mps;
-constexpr auto kMaxAcceleration = 1_mps_sq;
+inline constexpr auto kMaxSpeed = 3_mps;
+inline constexpr auto kMaxAcceleration = 1_mps_sq;
 
 // Reasonable baseline values for a RAMSETE follower in units of meters and
 // seconds
-constexpr auto kRamseteB = 2.0 * 1_rad * 1_rad / (1_m * 1_m);
-constexpr auto kRamseteZeta = 0.7 / 1_rad;
+inline constexpr auto kRamseteB = 2.0 * 1_rad * 1_rad / (1_m * 1_m);
+inline constexpr auto kRamseteZeta = 0.7 / 1_rad;
 }  // namespace AutoConstants
 
 namespace OIConstants {
-constexpr int kDriverControllerPort = 0;
+inline constexpr int kDriverControllerPort = 0;
 }  // namespace OIConstants
diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/subsystems/DriveSubsystem.h
index 8ea14da..e1580e1 100644
--- a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/subsystems/DriveSubsystem.h
+++ b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/subsystems/DriveSubsystem.h
@@ -9,7 +9,6 @@
 #include <frc/drive/DifferentialDrive.h>
 #include <frc/geometry/Pose2d.h>
 #include <frc/kinematics/DifferentialDriveOdometry.h>
-#include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <frc2/command/SubsystemBase.h>
 #include <units/voltage.h>
@@ -122,14 +121,9 @@
   frc::PWMSparkMax m_right1;
   frc::PWMSparkMax m_right2;
 
-  // The motors on the left side of the drive
-  frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
-
-  // The motors on the right side of the drive
-  frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
-
   // The robot's drive
-  frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
+  frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); },
+                                 [&](double output) { m_right1.Set(output); }};
 
   // The left-side drive encoder
   frc::Encoder m_leftEncoder;
diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Drivetrain.cpp
index 8c1e632..9ce08e9 100644
--- a/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Drivetrain.cpp
@@ -12,8 +12,8 @@
   const double rightOutput = m_rightPIDController.Calculate(
       m_rightEncoder.GetRate(), speeds.right.value());
 
-  m_leftGroup.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
-  m_rightGroup.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);
+  m_leftLeader.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
+  m_rightLeader.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);
 }
 
 void Drivetrain::Drive(units::meters_per_second_t xSpeed,
diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h
index 341cd38..39511c7 100644
--- a/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/RamseteController/include/Drivetrain.h
@@ -12,7 +12,6 @@
 #include <frc/controller/SimpleMotorFeedforward.h>
 #include <frc/kinematics/DifferentialDriveKinematics.h>
 #include <frc/kinematics/DifferentialDriveOdometry.h>
-#include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <units/angular_velocity.h>
 #include <units/length.h>
@@ -25,10 +24,13 @@
   Drivetrain() {
     m_gyro.Reset();
 
+    m_leftLeader.AddFollower(m_leftFollower);
+    m_rightLeader.AddFollower(m_rightFollower);
+
     // We need to invert one side of the drivetrain so that positive voltages
     // result in both sides moving forward. Depending on how your robot's
     // gearbox is constructed, you might have to invert the left side instead.
-    m_rightGroup.SetInverted(true);
+    m_rightLeader.SetInverted(true);
 
     // Set the distance per pulse for the drive encoders. We can simply use the
     // distance traveled for one rotation of the wheel divided by the encoder
@@ -64,9 +66,6 @@
   frc::PWMSparkMax m_rightLeader{3};
   frc::PWMSparkMax m_rightFollower{4};
 
-  frc::MotorControllerGroup m_leftGroup{m_leftLeader, m_leftFollower};
-  frc::MotorControllerGroup m_rightGroup{m_rightLeader, m_rightFollower};
-
   frc::Encoder m_leftEncoder{0, 1};
   frc::Encoder m_rightEncoder{2, 3};
 
diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp
index 98ff0ca..e03ce43 100644
--- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp
@@ -9,10 +9,16 @@
 #include <frc2/command/Commands.h>
 
 Drive::Drive() {
+  wpi::SendableRegistry::AddChild(&m_drive, &m_leftLeader);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_rightLeader);
+
+  m_leftLeader.AddFollower(m_leftFollower);
+  m_rightLeader.AddFollower(m_rightFollower);
+
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
-  m_rightMotors.SetInverted(true);
+  m_rightLeader.SetInverted(true);
 
   // Sets the distance per pulse for the encoders
   m_leftEncoder.SetDistancePerPulse(DriveConstants::kEncoderDistancePerPulse);
diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Constants.h
index 330eeba..a552c44 100644
--- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Constants.h
@@ -13,63 +13,63 @@
 #include <units/voltage.h>
 
 namespace DriveConstants {
-constexpr int kLeftMotor1Port = 0;
-constexpr int kLeftMotor2Port = 1;
-constexpr int kRightMotor1Port = 2;
-constexpr int kRightMotor2Port = 3;
+inline constexpr int kLeftMotor1Port = 0;
+inline constexpr int kLeftMotor2Port = 1;
+inline constexpr int kRightMotor1Port = 2;
+inline constexpr int kRightMotor2Port = 3;
 
-constexpr int kLeftEncoderPorts[]{0, 1};
-constexpr int kRightEncoderPorts[]{2, 3};
-constexpr bool kLeftEncoderReversed = false;
-constexpr bool kRightEncoderReversed = true;
+inline constexpr int kLeftEncoderPorts[]{0, 1};
+inline constexpr int kRightEncoderPorts[]{2, 3};
+inline constexpr bool kLeftEncoderReversed = false;
+inline constexpr bool kRightEncoderReversed = true;
 
-constexpr double kEncoderCPR = 1024;
-constexpr units::meter_t kWheelDiameter = 6.0_in;
-constexpr double kEncoderDistancePerPulse =
+inline constexpr double kEncoderCPR = 1024;
+inline constexpr units::meter_t kWheelDiameter = 6.0_in;
+inline constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
     ((kWheelDiameter * std::numbers::pi) / kEncoderCPR).value();
 
 }  // namespace DriveConstants
 
 namespace IntakeConstants {
-constexpr int kMotorPort = 6;
-constexpr int kSolenoidPorts[]{0, 1};
+inline constexpr int kMotorPort = 6;
+inline constexpr int kSolenoidPorts[]{0, 1};
 }  // namespace IntakeConstants
 
 namespace StorageConstants {
-constexpr int kMotorPort = 7;
-constexpr int kBallSensorPort = 6;
+inline constexpr int kMotorPort = 7;
+inline constexpr int kBallSensorPort = 6;
 }  // namespace StorageConstants
 
 namespace ShooterConstants {
-constexpr int kEncoderPorts[]{4, 5};
-constexpr bool kEncoderReversed = false;
-constexpr double kEncoderCPR = 1024;
-constexpr double kEncoderDistancePerPulse =
+inline constexpr int kEncoderPorts[]{4, 5};
+inline constexpr bool kEncoderReversed = false;
+inline constexpr double kEncoderCPR = 1024;
+inline constexpr double kEncoderDistancePerPulse =
     // Distance units will be rotations
     1.0 / kEncoderCPR;
 
-constexpr int kShooterMotorPort = 4;
-constexpr int kFeederMotorPort = 5;
+inline constexpr int kShooterMotorPort = 4;
+inline constexpr int kFeederMotorPort = 5;
 
-constexpr auto kShooterFree = 5300_tps;
-constexpr auto kShooterTarget = 4000_tps;
-constexpr auto kShooterTolerance = 50_tps;
+inline constexpr auto kShooterFree = 5300_tps;
+inline constexpr auto kShooterTarget = 4000_tps;
+inline constexpr auto kShooterTolerance = 50_tps;
 
 // These are not real PID gains, and will have to be tuned for your specific
 // robot.
-constexpr double kP = 1;
+inline constexpr double kP = 1;
 
-constexpr units::volt_t kS = 0.05_V;
-constexpr auto kV =
+inline constexpr units::volt_t kS = 0.05_V;
+inline constexpr auto kV =
     // Should have value 12V at free speed...
     12.0_V / kShooterFree;
 
-constexpr double kFeederSpeed = 0.5;
+inline constexpr double kFeederSpeed = 0.5;
 }  // namespace ShooterConstants
 
 namespace OIConstants {
-constexpr int kDriverControllerPort = 0;
+inline constexpr int kDriverControllerPort = 0;
 }  // namespace OIConstants
 
 namespace AutoConstants {
diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h
index ac96c52..8432e57 100644
--- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h
+++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h
@@ -8,7 +8,6 @@
 
 #include <frc/Encoder.h>
 #include <frc/drive/DifferentialDrive.h>
-#include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <frc2/command/CommandPtr.h>
 #include <frc2/command/SubsystemBase.h>
@@ -45,10 +44,9 @@
   frc::PWMSparkMax m_rightLeader{DriveConstants::kRightMotor1Port};
   frc::PWMSparkMax m_rightFollower{DriveConstants::kRightMotor2Port};
 
-  frc::MotorControllerGroup m_leftMotors{m_leftLeader, m_leftFollower};
-  frc::MotorControllerGroup m_rightMotors{m_rightLeader, m_rightFollower};
-
-  frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
+  frc::DifferentialDrive m_drive{
+      [&](double output) { m_leftLeader.Set(output); },
+      [&](double output) { m_rightLeader.Set(output); }};
 
   frc::Encoder m_leftEncoder{DriveConstants::kLeftEncoderPorts[0],
                              DriveConstants::kLeftEncoderPorts[1],
diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp
index 979f8a0..1d212d5 100644
--- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp
@@ -15,6 +15,9 @@
 // The Romi has onboard encoders that are hardcoded
 // to use DIO pins 4/5 and 6/7 for the left and right
 Drivetrain::Drivetrain() {
+  wpi::SendableRegistry::AddChild(&m_drive, &m_leftMotor);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_rightMotor);
+
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Constants.h
index e5cee33..dddb741 100644
--- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Constants.h
@@ -14,6 +14,6 @@
  */
 
 namespace DriveConstants {
-constexpr double kCountsPerRevolution = 1440.0;
-constexpr double kWheelDiameterInch = 2.75;
+inline constexpr double kCountsPerRevolution = 1440.0;
+inline constexpr double kWheelDiameterInch = 2.75;
 }  // namespace DriveConstants
diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h
index ace7d33..d679178 100644
--- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h
@@ -114,7 +114,9 @@
   frc::Encoder m_leftEncoder{4, 5};
   frc::Encoder m_rightEncoder{6, 7};
 
-  frc::DifferentialDrive m_drive{m_leftMotor, m_rightMotor};
+  frc::DifferentialDrive m_drive{
+      [&](double output) { m_leftMotor.Set(output); },
+      [&](double output) { m_rightMotor.Set(output); }};
 
   frc::RomiGyro m_gyro;
   frc::BuiltInAccelerometer m_accelerometer;
diff --git a/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/RobotContainer.cpp
index 69895cb..df5ba8c 100644
--- a/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/RobotContainer.cpp
@@ -4,9 +4,17 @@
 
 #include "RobotContainer.h"
 
+#include <frc/smartdashboard/SmartDashboard.h>
+
 RobotContainer::RobotContainer() {
   // Initialize all of your commands and subsystems here
 
+  m_chooser.SetDefaultOption("ONE", CommandSelector::ONE);
+  m_chooser.AddOption("TWO", CommandSelector::TWO);
+  m_chooser.AddOption("THREE", CommandSelector::THREE);
+
+  frc::SmartDashboard::PutData("Auto Chooser", &m_chooser);
+
   // Configure the button bindings
   ConfigureButtonBindings();
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/Constants.h
index ae5d02d..e07663a 100644
--- a/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/Constants.h
@@ -15,5 +15,5 @@
  */
 
 namespace OIConstants {
-constexpr int kDriverControllerPort = 0;
+inline constexpr int kDriverControllerPort = 0;
 }  // namespace OIConstants
diff --git a/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/RobotContainer.h
index a1a2c86..ce5e26d 100644
--- a/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/RobotContainer.h
+++ b/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/RobotContainer.h
@@ -4,7 +4,9 @@
 
 #pragma once
 
+#include <frc/smartdashboard/SendableChooser.h>
 #include <frc2/command/Command.h>
+#include <frc2/command/CommandPtr.h>
 #include <frc2/command/Commands.h>
 
 /**
@@ -24,10 +26,8 @@
   // The enum used as keys for selecting the command to run.
   enum CommandSelector { ONE, TWO, THREE };
 
-  // An example selector method for the selectcommand.  Returns the selector
-  // that will select which command to run.  Can base this choice on logical
-  // conditions evaluated at runtime.
-  CommandSelector Select() { return ONE; }
+  // An example of how command selector may be used with SendableChooser
+  frc::SendableChooser<CommandSelector> m_chooser;
 
   // The robot's subsystems and commands are defined here...
 
@@ -36,7 +36,7 @@
   // takes a generic type, so the selector does not have to be an enum; it could
   // be any desired type (string, integer, boolean, double...)
   frc2::CommandPtr m_exampleSelectCommand = frc2::cmd::Select<CommandSelector>(
-      [this] { return Select(); },
+      [this] { return m_chooser.GetSelected(); },
       // Maps selector values to commands
       std::pair{ONE, frc2::cmd::Print("Command one was selected!")},
       std::pair{TWO, frc2::cmd::Print("Command two was selected!")},
diff --git a/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp
index b951f18..b532bcb 100644
--- a/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp
@@ -30,6 +30,9 @@
 class Robot : public frc::TimedRobot {
  public:
   void RobotInit() override {
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_left);
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_right);
+
     // Add a widget titled 'Max Speed' with a number slider.
     m_maxSpeed = frc::Shuffleboard::GetTab("Configuration")
                      .Add("Max Speed", 1)
@@ -65,7 +68,9 @@
   frc::PWMSparkMax m_right{1};
   frc::PWMSparkMax m_elevatorMotor{2};
 
-  frc::DifferentialDrive m_robotDrive{m_left, m_right};
+  frc::DifferentialDrive m_robotDrive{
+      [&](double output) { m_left.Set(output); },
+      [&](double output) { m_right.Set(output); }};
 
   frc::Joystick m_stick{0};
 
diff --git a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp
index 93d0889..e0b63ca 100644
--- a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp
@@ -14,8 +14,8 @@
   double rightOutput = m_rightPIDController.Calculate(m_rightEncoder.GetRate(),
                                                       speeds.right.value());
 
-  m_leftGroup.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
-  m_rightGroup.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);
+  m_leftLeader.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
+  m_rightLeader.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);
 }
 
 void Drivetrain::Drive(units::meters_per_second_t xSpeed,
@@ -43,9 +43,9 @@
   // simulation, and write the simulated positions and velocities to our
   // simulated encoder and gyro. We negate the right side so that positive
   // voltages make the right side move forward.
-  m_drivetrainSimulator.SetInputs(units::volt_t{m_leftGroup.Get()} *
+  m_drivetrainSimulator.SetInputs(units::volt_t{m_leftLeader.Get()} *
                                       frc::RobotController::GetInputVoltage(),
-                                  units::volt_t{m_rightGroup.Get()} *
+                                  units::volt_t{m_rightLeader.Get()} *
                                       frc::RobotController::GetInputVoltage());
   m_drivetrainSimulator.Update(20_ms);
 
diff --git a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h
index 4c274fe..ca82547 100644
--- a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.h
@@ -12,7 +12,6 @@
 #include <frc/controller/SimpleMotorFeedforward.h>
 #include <frc/kinematics/DifferentialDriveKinematics.h>
 #include <frc/kinematics/DifferentialDriveOdometry.h>
-#include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <frc/simulation/AnalogGyroSim.h>
 #include <frc/simulation/DifferentialDrivetrainSim.h>
@@ -33,10 +32,13 @@
   Drivetrain() {
     m_gyro.Reset();
 
+    m_leftLeader.AddFollower(m_leftFollower);
+    m_rightLeader.AddFollower(m_rightFollower);
+
     // We need to invert one side of the drivetrain so that positive voltages
     // result in both sides moving forward. Depending on how your robot's
     // gearbox is constructed, you might have to invert the left side instead.
-    m_rightGroup.SetInverted(true);
+    m_rightLeader.SetInverted(true);
 
     // Set the distance per pulse for the drive encoders. We can simply use the
     // distance traveled for one rotation of the wheel divided by the encoder
@@ -49,7 +51,7 @@
     m_leftEncoder.Reset();
     m_rightEncoder.Reset();
 
-    m_rightGroup.SetInverted(true);
+    m_rightLeader.SetInverted(true);
 
     frc::SmartDashboard::PutData("Field", &m_fieldSim);
   }
@@ -80,9 +82,6 @@
   frc::PWMSparkMax m_rightLeader{3};
   frc::PWMSparkMax m_rightFollower{4};
 
-  frc::MotorControllerGroup m_leftGroup{m_leftLeader, m_leftFollower};
-  frc::MotorControllerGroup m_rightGroup{m_rightLeader, m_rightFollower};
-
   frc::Encoder m_leftEncoder{0, 1};
   frc::Encoder m_rightEncoder{2, 3};
 
diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp
index f6a9eea..38e9262 100644
--- a/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp
@@ -117,7 +117,7 @@
       goal = {kLoweredPosition, 0_rad_per_s};
     }
     m_lastProfiledReference =
-        m_profile.Calculate(20_ms, goal, m_lastProfiledReference);
+        m_profile.Calculate(20_ms, m_lastProfiledReference, goal);
 
     m_loop.SetNextR(frc::Vectord<2>{m_lastProfiledReference.position.value(),
                                     m_lastProfiledReference.velocity.value()});
diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp
index 15d8596..ecef64a 100644
--- a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp
@@ -14,10 +14,16 @@
 using namespace DriveConstants;
 
 DriveSubsystem::DriveSubsystem() {
+  wpi::SendableRegistry::AddChild(&m_drive, &m_left1);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_right1);
+
+  m_left1.AddFollower(m_left2);
+  m_right1.AddFollower(m_right2);
+
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
-  m_rightMotors.SetInverted(true);
+  m_right1.SetInverted(true);
 
   // Set the distance per pulse for the encoders
   m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
@@ -40,10 +46,9 @@
   // simulation, and write the simulated positions and velocities to our
   // simulated encoder and gyro. We negate the right side so that positive
   // voltages make the right side move forward.
-  m_drivetrainSimulator.SetInputs(units::volt_t{m_leftMotors.Get()} *
-                                      frc::RobotController::GetInputVoltage(),
-                                  units::volt_t{m_rightMotors.Get()} *
-                                      frc::RobotController::GetInputVoltage());
+  m_drivetrainSimulator.SetInputs(
+      units::volt_t{m_left1.Get()} * frc::RobotController::GetInputVoltage(),
+      units::volt_t{m_right1.Get()} * frc::RobotController::GetInputVoltage());
   m_drivetrainSimulator.Update(20_ms);
 
   m_leftEncoderSim.SetDistance(m_drivetrainSimulator.GetLeftPosition().value());
@@ -63,8 +68,8 @@
 }
 
 void DriveSubsystem::TankDriveVolts(units::volt_t left, units::volt_t right) {
-  m_leftMotors.SetVoltage(left);
-  m_rightMotors.SetVoltage(right);
+  m_left1.SetVoltage(left);
+  m_right1.SetVoltage(right);
   m_drive.Feed();
 }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h
index d8080ca..103204a 100644
--- a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h
@@ -27,22 +27,22 @@
  */
 
 namespace DriveConstants {
-constexpr int kLeftMotor1Port = 0;
-constexpr int kLeftMotor2Port = 1;
-constexpr int kRightMotor1Port = 2;
-constexpr int kRightMotor2Port = 3;
+inline constexpr int kLeftMotor1Port = 0;
+inline constexpr int kLeftMotor2Port = 1;
+inline constexpr int kRightMotor1Port = 2;
+inline constexpr int kRightMotor2Port = 3;
 
-constexpr int kLeftEncoderPorts[]{0, 1};
-constexpr int kRightEncoderPorts[]{2, 3};
-constexpr bool kLeftEncoderReversed = false;
-constexpr bool kRightEncoderReversed = true;
+inline constexpr int kLeftEncoderPorts[]{0, 1};
+inline constexpr int kRightEncoderPorts[]{2, 3};
+inline constexpr bool kLeftEncoderReversed = false;
+inline constexpr bool kRightEncoderReversed = true;
 
-constexpr auto kTrackwidth = 0.69_m;
+inline constexpr auto kTrackwidth = 0.69_m;
 extern const frc::DifferentialDriveKinematics kDriveKinematics;
 
-constexpr int kEncoderCPR = 1024;
-constexpr auto kWheelDiameter = 6_in;
-constexpr double kEncoderDistancePerPulse =
+inline constexpr int kEncoderCPR = 1024;
+inline constexpr auto kWheelDiameter = 6_in;
+inline constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
     (kWheelDiameter.value() * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
@@ -52,33 +52,33 @@
 // theoretically for *your* robot's drive. The Robot Characterization
 // Toolsuite provides a convenient tool for obtaining these values for your
 // robot.
-constexpr auto ks = 0.22_V;
-constexpr auto kv = 1.98 * 1_V / 1_mps;
-constexpr auto ka = 0.2 * 1_V / 1_mps_sq;
+inline constexpr auto ks = 0.22_V;
+inline constexpr auto kv = 1.98 * 1_V / 1_mps;
+inline constexpr auto ka = 0.2 * 1_V / 1_mps_sq;
 
-constexpr auto kvAngular = 1.5 * 1_V / 1_mps;
-constexpr auto kaAngular = 0.3 * 1_V / 1_mps_sq;
+inline constexpr auto kvAngular = 1.5 * 1_V / 1_mps;
+inline constexpr auto kaAngular = 0.3 * 1_V / 1_mps_sq;
 
 extern const frc::LinearSystem<2, 2, 2> kDrivetrainPlant;
 
 // Example values only -- use what's on your physical robot!
-constexpr auto kDrivetrainGearbox = frc::DCMotor::CIM(2);
-constexpr auto kDrivetrainGearing = 8.0;
+inline constexpr auto kDrivetrainGearbox = frc::DCMotor::CIM(2);
+inline constexpr auto kDrivetrainGearing = 8.0;
 
 // Example value only - as above, this must be tuned for your drive!
-constexpr double kPDriveVel = 8.5;
+inline constexpr double kPDriveVel = 8.5;
 }  // namespace DriveConstants
 
 namespace AutoConstants {
-constexpr auto kMaxSpeed = 3_mps;
-constexpr auto kMaxAcceleration = 3_mps_sq;
+inline constexpr auto kMaxSpeed = 3_mps;
+inline constexpr auto kMaxAcceleration = 3_mps_sq;
 
 // Reasonable baseline values for a RAMSETE follower in units of meters and
 // seconds
-constexpr auto kRamseteB = 2 * 1_rad * 1_rad / (1_m * 1_m);
-constexpr auto kRamseteZeta = 0.7 / 1_rad;
+inline constexpr auto kRamseteB = 2 * 1_rad * 1_rad / (1_m * 1_m);
+inline constexpr auto kRamseteZeta = 0.7 / 1_rad;
 }  // namespace AutoConstants
 
 namespace OIConstants {
-constexpr int kDriverControllerPort = 0;
+inline constexpr int kDriverControllerPort = 0;
 }  // namespace OIConstants
diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h
index 57392c7..5e41201 100644
--- a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h
+++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h
@@ -9,7 +9,6 @@
 #include <frc/drive/DifferentialDrive.h>
 #include <frc/geometry/Pose2d.h>
 #include <frc/kinematics/DifferentialDriveOdometry.h>
-#include <frc/motorcontrol/MotorControllerGroup.h>
 #include <frc/motorcontrol/PWMSparkMax.h>
 #include <frc/simulation/ADXRS450_GyroSim.h>
 #include <frc/simulation/DifferentialDrivetrainSim.h>
@@ -133,14 +132,9 @@
   frc::PWMSparkMax m_right1{DriveConstants::kRightMotor1Port};
   frc::PWMSparkMax m_right2{DriveConstants::kRightMotor2Port};
 
-  // The motors on the left side of the drive
-  frc::MotorControllerGroup m_leftMotors{m_left1, m_left2};
-
-  // The motors on the right side of the drive
-  frc::MotorControllerGroup m_rightMotors{m_right1, m_right2};
-
   // The robot's drive
-  frc::DifferentialDrive m_drive{m_leftMotors, m_rightMotors};
+  frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); },
+                                 [&](double output) { m_right1.Set(output); }};
 
   // The left-side drive encoder
   frc::Encoder m_leftEncoder{DriveConstants::kLeftEncoderPorts[0],
diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp
index 3b83793..ceadd83 100644
--- a/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp
@@ -117,7 +117,7 @@
       goal = {kLoweredPosition, 0_fps};
     }
     m_lastProfiledReference =
-        m_profile.Calculate(20_ms, goal, m_lastProfiledReference);
+        m_profile.Calculate(20_ms, m_lastProfiledReference, goal);
 
     m_loop.SetNextR(frc::Vectord<2>{m_lastProfiledReference.position.value(),
                                     m_lastProfiledReference.velocity.value()});
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/Robot.cpp
index c7eab48..c4c1661 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/Robot.cpp
@@ -37,7 +37,7 @@
 void Robot::AutonomousInit() {
   m_autonomousCommand = m_container.GetAutonomousCommand();
 
-  if (m_autonomousCommand != nullptr) {
+  if (m_autonomousCommand) {
     m_autonomousCommand->Schedule();
   }
 }
@@ -49,9 +49,9 @@
   // teleop starts running. If you want the autonomous to
   // continue until interrupted by another command, remove
   // this line or comment it out.
-  if (m_autonomousCommand != nullptr) {
+  if (m_autonomousCommand) {
     m_autonomousCommand->Cancel();
-    m_autonomousCommand = nullptr;
+    m_autonomousCommand.reset();
   }
 }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp
index 4bbbe0c..2ca4b71 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp
@@ -11,6 +11,7 @@
 #include <frc/shuffleboard/Shuffleboard.h>
 #include <frc/trajectory/Trajectory.h>
 #include <frc/trajectory/TrajectoryGenerator.h>
+#include <frc2/command/Commands.h>
 #include <frc2/command/InstantCommand.h>
 #include <frc2/command/SequentialCommandGroup.h>
 #include <frc2/command/SwerveControllerCommand.h>
@@ -48,7 +49,7 @@
 
 void RobotContainer::ConfigureButtonBindings() {}
 
-frc2::Command* RobotContainer::GetAutonomousCommand() {
+frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
   // Set up config for trajectory
   frc::TrajectoryConfig config(AutoConstants::kMaxSpeed,
                                AutoConstants::kMaxAcceleration);
@@ -73,24 +74,32 @@
   thetaController.EnableContinuousInput(units::radian_t{-std::numbers::pi},
                                         units::radian_t{std::numbers::pi});
 
-  frc2::SwerveControllerCommand<4> swerveControllerCommand(
-      exampleTrajectory, [this]() { return m_drive.GetPose(); },
+  frc2::CommandPtr swerveControllerCommand =
+      frc2::SwerveControllerCommand<4>(
+          exampleTrajectory, [this]() { return m_drive.GetPose(); },
 
-      m_drive.kDriveKinematics,
+          m_drive.kDriveKinematics,
 
-      frc::PIDController{AutoConstants::kPXController, 0, 0},
-      frc::PIDController{AutoConstants::kPYController, 0, 0}, thetaController,
+          frc::PIDController{AutoConstants::kPXController, 0, 0},
+          frc::PIDController{AutoConstants::kPYController, 0, 0},
+          thetaController,
 
-      [this](auto moduleStates) { m_drive.SetModuleStates(moduleStates); },
+          [this](auto moduleStates) { m_drive.SetModuleStates(moduleStates); },
 
-      {&m_drive});
+          {&m_drive})
+          .ToPtr();
 
-  // Reset odometry to the starting pose of the trajectory.
-  m_drive.ResetOdometry(exampleTrajectory.InitialPose());
-
-  // no auto
-  return new frc2::SequentialCommandGroup(
+  // Reset odometry to the initial pose of the trajectory, run path following
+  // command, then stop at the end.
+  return frc2::cmd::Sequence(
+      frc2::InstantCommand(
+          [this, &exampleTrajectory]() {
+            m_drive.ResetOdometry(exampleTrajectory.InitialPose());
+          },
+          {})
+          .ToPtr(),
       std::move(swerveControllerCommand),
       frc2::InstantCommand(
-          [this]() { m_drive.Drive(0_mps, 0_mps, 0_rad_per_s, false); }, {}));
+          [this] { m_drive.Drive(0_mps, 0_mps, 0_rad_per_s, false); }, {})
+          .ToPtr());
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/SwerveModule.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/SwerveModule.cpp
index dc1cdb0..d565e84 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/SwerveModule.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/SwerveModule.cpp
@@ -11,8 +11,8 @@
 #include "Constants.h"
 
 SwerveModule::SwerveModule(int driveMotorChannel, int turningMotorChannel,
-                           const int driveEncoderPorts[],
-                           const int turningEncoderPorts[],
+                           const int driveEncoderPorts[2],
+                           const int turningEncoderPorts[2],
                            bool driveEncoderReversed,
                            bool turningEncoderReversed)
     : m_driveMotor(driveMotorChannel),
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h
index 779927d..5e95629 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h
@@ -29,80 +29,80 @@
  */
 
 namespace DriveConstants {
-constexpr int kFrontLeftDriveMotorPort = 0;
-constexpr int kRearLeftDriveMotorPort = 2;
-constexpr int kFrontRightDriveMotorPort = 4;
-constexpr int kRearRightDriveMotorPort = 6;
+inline constexpr int kFrontLeftDriveMotorPort = 0;
+inline constexpr int kRearLeftDriveMotorPort = 2;
+inline constexpr int kFrontRightDriveMotorPort = 4;
+inline constexpr int kRearRightDriveMotorPort = 6;
 
-constexpr int kFrontLeftTurningMotorPort = 1;
-constexpr int kRearLeftTurningMotorPort = 3;
-constexpr int kFrontRightTurningMotorPort = 5;
-constexpr int kRearRightTurningMotorPort = 7;
+inline constexpr int kFrontLeftTurningMotorPort = 1;
+inline constexpr int kRearLeftTurningMotorPort = 3;
+inline constexpr int kFrontRightTurningMotorPort = 5;
+inline constexpr int kRearRightTurningMotorPort = 7;
 
-constexpr int kFrontLeftTurningEncoderPorts[2]{0, 1};
-constexpr int kRearLeftTurningEncoderPorts[2]{2, 3};
-constexpr int kFrontRightTurningEncoderPorts[2]{4, 5};
-constexpr int kRearRightTurningEncoderPorts[2]{6, 7};
+inline constexpr int kFrontLeftTurningEncoderPorts[2]{0, 1};
+inline constexpr int kRearLeftTurningEncoderPorts[2]{2, 3};
+inline constexpr int kFrontRightTurningEncoderPorts[2]{4, 5};
+inline constexpr int kRearRightTurningEncoderPorts[2]{6, 7};
 
-constexpr bool kFrontLeftTurningEncoderReversed = false;
-constexpr bool kRearLeftTurningEncoderReversed = true;
-constexpr bool kFrontRightTurningEncoderReversed = false;
-constexpr bool kRearRightTurningEncoderReversed = true;
+inline constexpr bool kFrontLeftTurningEncoderReversed = false;
+inline constexpr bool kRearLeftTurningEncoderReversed = true;
+inline constexpr bool kFrontRightTurningEncoderReversed = false;
+inline constexpr bool kRearRightTurningEncoderReversed = true;
 
-constexpr int kFrontLeftDriveEncoderPorts[2]{8, 9};
-constexpr int kRearLeftDriveEncoderPorts[2]{10, 11};
-constexpr int kFrontRightDriveEncoderPorts[2]{12, 13};
-constexpr int kRearRightDriveEncoderPorts[2]{14, 15};
+inline constexpr int kFrontLeftDriveEncoderPorts[2]{8, 9};
+inline constexpr int kRearLeftDriveEncoderPorts[2]{10, 11};
+inline constexpr int kFrontRightDriveEncoderPorts[2]{12, 13};
+inline constexpr int kRearRightDriveEncoderPorts[2]{14, 15};
 
-constexpr bool kFrontLeftDriveEncoderReversed = false;
-constexpr bool kRearLeftDriveEncoderReversed = true;
-constexpr bool kFrontRightDriveEncoderReversed = false;
-constexpr bool kRearRightDriveEncoderReversed = true;
+inline constexpr bool kFrontLeftDriveEncoderReversed = false;
+inline constexpr bool kRearLeftDriveEncoderReversed = true;
+inline constexpr bool kFrontRightDriveEncoderReversed = false;
+inline constexpr bool kRearRightDriveEncoderReversed = true;
 
 // If you call DriveSubsystem::Drive with a different period make sure to update
 // this.
-constexpr units::second_t kDrivePeriod = frc::TimedRobot::kDefaultPeriod;
+inline constexpr units::second_t kDrivePeriod = frc::TimedRobot::kDefaultPeriod;
 
 // These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
 // These characterization values MUST be determined either experimentally or
 // theoretically for *your* robot's drive. The SysId tool provides a convenient
 // method for obtaining these values for your robot.
-constexpr auto ks = 1_V;
-constexpr auto kv = 0.8 * 1_V * 1_s / 1_m;
-constexpr auto ka = 0.15 * 1_V * 1_s * 1_s / 1_m;
+inline constexpr auto ks = 1_V;
+inline constexpr auto kv = 0.8 * 1_V * 1_s / 1_m;
+inline constexpr auto ka = 0.15 * 1_V * 1_s * 1_s / 1_m;
 
 // Example value only - as above, this must be tuned for your drive!
-constexpr double kPFrontLeftVel = 0.5;
-constexpr double kPRearLeftVel = 0.5;
-constexpr double kPFrontRightVel = 0.5;
-constexpr double kPRearRightVel = 0.5;
+inline constexpr double kPFrontLeftVel = 0.5;
+inline constexpr double kPRearLeftVel = 0.5;
+inline constexpr double kPFrontRightVel = 0.5;
+inline constexpr double kPRearRightVel = 0.5;
 }  // namespace DriveConstants
 
 namespace ModuleConstants {
-constexpr int kEncoderCPR = 1024;
-constexpr double kWheelDiameterMeters = 0.15;
-constexpr double kDriveEncoderDistancePerPulse =
+inline constexpr int kEncoderCPR = 1024;
+inline constexpr double kWheelDiameterMeters = 0.15;
+inline constexpr double kDriveEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
     (kWheelDiameterMeters * std::numbers::pi) /
     static_cast<double>(kEncoderCPR);
 
-constexpr double kTurningEncoderDistancePerPulse =
+inline constexpr double kTurningEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
     (std::numbers::pi * 2) / static_cast<double>(kEncoderCPR);
 
-constexpr double kPModuleTurningController = 1;
-constexpr double kPModuleDriveController = 1;
+inline constexpr double kPModuleTurningController = 1;
+inline constexpr double kPModuleDriveController = 1;
 }  // namespace ModuleConstants
 
 namespace AutoConstants {
-constexpr auto kMaxSpeed = 3_mps;
-constexpr auto kMaxAcceleration = 3_mps_sq;
-constexpr auto kMaxAngularSpeed = 3.142_rad_per_s;
-constexpr auto kMaxAngularAcceleration = 3.142_rad_per_s_sq;
+inline constexpr auto kMaxSpeed = 3_mps;
+inline constexpr auto kMaxAcceleration = 3_mps_sq;
+inline constexpr auto kMaxAngularSpeed = 3.142_rad_per_s;
+inline constexpr auto kMaxAngularAcceleration = 3.142_rad_per_s_sq;
 
-constexpr double kPXController = 0.5;
-constexpr double kPYController = 0.5;
-constexpr double kPThetaController = 0.5;
+inline constexpr double kPXController = 0.5;
+inline constexpr double kPYController = 0.5;
+inline constexpr double kPThetaController = 0.5;
 
 //
 
@@ -112,5 +112,5 @@
 }  // namespace AutoConstants
 
 namespace OIConstants {
-constexpr int kDriverControllerPort = 0;
+inline constexpr int kDriverControllerPort = 0;
 }  // namespace OIConstants
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Robot.h
index a82f2ac..de9c814 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Robot.h
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Robot.h
@@ -4,6 +4,8 @@
 
 #pragma once
 
+#include <optional>
+
 #include <frc/TimedRobot.h>
 #include <frc2/command/Command.h>
 
@@ -24,7 +26,7 @@
  private:
   // Have it null by default so that if testing teleop it
   // doesn't have undefined behavior and potentially crash.
-  frc2::Command* m_autonomousCommand = nullptr;
+  std::optional<frc2::CommandPtr> m_autonomousCommand;
 
   RobotContainer m_container;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/RobotContainer.h b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/RobotContainer.h
index 3466121..4c79164 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/RobotContainer.h
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/RobotContainer.h
@@ -9,6 +9,7 @@
 #include <frc/controller/ProfiledPIDController.h>
 #include <frc/smartdashboard/SendableChooser.h>
 #include <frc2/command/Command.h>
+#include <frc2/command/CommandPtr.h>
 #include <frc2/command/InstantCommand.h>
 #include <frc2/command/PIDCommand.h>
 #include <frc2/command/ParallelRaceGroup.h>
@@ -28,7 +29,7 @@
  public:
   RobotContainer();
 
-  frc2::Command* GetAutonomousCommand();
+  frc2::CommandPtr GetAutonomousCommand();
 
  private:
   // The driver's controller
@@ -39,8 +40,5 @@
   // The robot's subsystems
   DriveSubsystem m_drive;
 
-  // The chooser for the autonomous routines
-  frc::SendableChooser<frc2::Command*> m_chooser;
-
   void ConfigureButtonBindings();
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp
index a365f7f..188e944 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp
@@ -15,7 +15,8 @@
   auto states =
       m_kinematics.ToSwerveModuleStates(frc::ChassisSpeeds::Discretize(
           fieldRelative ? frc::ChassisSpeeds::FromFieldRelativeSpeeds(
-                              xSpeed, ySpeed, rot, m_gyro.GetRotation2d())
+                              xSpeed, ySpeed, rot,
+                              m_poseEstimator.GetEstimatedPosition().Rotation())
                         : frc::ChassisSpeeds{xSpeed, ySpeed, rot},
           period));
 
diff --git a/wpilibcExamples/src/main/cpp/examples/SysId/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SysId/cpp/Robot.cpp
new file mode 100644
index 0000000..5ecb68a
--- /dev/null
+++ b/wpilibcExamples/src/main/cpp/examples/SysId/cpp/Robot.cpp
@@ -0,0 +1,55 @@
+// 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 "Robot.h"

+

+#include <frc2/command/CommandScheduler.h>

+

+void Robot::RobotInit() {}

+

+void Robot::RobotPeriodic() {

+  frc2::CommandScheduler::GetInstance().Run();

+}

+

+void Robot::DisabledInit() {}

+

+void Robot::DisabledPeriodic() {}

+

+void Robot::DisabledExit() {}

+

+void Robot::AutonomousInit() {

+  m_autonomousCommand = m_container.GetAutonomousCommand();

+

+  if (m_autonomousCommand) {

+    m_autonomousCommand->Schedule();

+  }

+}

+

+void Robot::AutonomousPeriodic() {}

+

+void Robot::AutonomousExit() {}

+

+void Robot::TeleopInit() {

+  if (m_autonomousCommand) {

+    m_autonomousCommand->Cancel();

+  }

+}

+

+void Robot::TeleopPeriodic() {}

+

+void Robot::TeleopExit() {}

+

+void Robot::TestInit() {

+  frc2::CommandScheduler::GetInstance().CancelAll();

+}

+

+void Robot::TestPeriodic() {}

+

+void Robot::TestExit() {}

+

+#ifndef RUNNING_FRC_TESTS

+int main() {

+  return frc::StartRobot<Robot>();

+}

+#endif

diff --git a/wpilibcExamples/src/main/cpp/examples/SysId/cpp/SysIdRoutineBot.cpp b/wpilibcExamples/src/main/cpp/examples/SysId/cpp/SysIdRoutineBot.cpp
new file mode 100644
index 0000000..21f6992
--- /dev/null
+++ b/wpilibcExamples/src/main/cpp/examples/SysId/cpp/SysIdRoutineBot.cpp
@@ -0,0 +1,30 @@
+// 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 "SysIdRoutineBot.h"

+

+#include <frc2/command/Commands.h>

+

+SysIdRoutineBot::SysIdRoutineBot() {

+  ConfigureBindings();

+}

+

+void SysIdRoutineBot::ConfigureBindings() {

+  m_drive.SetDefaultCommand(m_drive.ArcadeDriveCommand(

+      [this] { return -m_driverController.GetLeftY(); },

+      [this] { return -m_driverController.GetRightX(); }));

+

+  m_driverController.A().WhileTrue(

+      m_drive.SysIdQuasistatic(frc2::sysid::Direction::kForward));

+  m_driverController.B().WhileTrue(

+      m_drive.SysIdQuasistatic(frc2::sysid::Direction::kReverse));

+  m_driverController.X().WhileTrue(

+      m_drive.SysIdDynamic(frc2::sysid::Direction::kForward));

+  m_driverController.Y().WhileTrue(

+      m_drive.SysIdDynamic(frc2::sysid::Direction::kReverse));

+}

+

+frc2::CommandPtr SysIdRoutineBot::GetAutonomousCommand() {

+  return m_drive.Run([] {});

+}

diff --git a/wpilibcExamples/src/main/cpp/examples/SysId/cpp/subsystems/Drive.cpp b/wpilibcExamples/src/main/cpp/examples/SysId/cpp/subsystems/Drive.cpp
new file mode 100644
index 0000000..c754976
--- /dev/null
+++ b/wpilibcExamples/src/main/cpp/examples/SysId/cpp/subsystems/Drive.cpp
@@ -0,0 +1,37 @@
+// 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 "subsystems/Drive.h"

+

+#include <frc2/command/Commands.h>

+

+Drive::Drive() {

+  m_leftMotor.AddFollower(frc::PWMSparkMax{constants::drive::kLeftMotor2Port});

+  m_rightMotor.AddFollower(

+      frc::PWMSparkMax{constants::drive::kRightMotor2Port});

+

+  m_rightMotor.SetInverted(true);

+

+  m_leftEncoder.SetDistancePerPulse(

+      constants::drive::kEncoderDistancePerPulse.value());

+  m_rightEncoder.SetDistancePerPulse(

+      constants::drive::kEncoderDistancePerPulse.value());

+

+  m_drive.SetSafetyEnabled(false);

+}

+

+frc2::CommandPtr Drive::ArcadeDriveCommand(std::function<double()> fwd,

+                                           std::function<double()> rot) {

+  return frc2::cmd::Run([this, fwd, rot] { m_drive.ArcadeDrive(fwd(), rot()); },

+                        {this})

+      .WithName("Arcade Drive");

+}

+

+frc2::CommandPtr Drive::SysIdQuasistatic(frc2::sysid::Direction direction) {

+  return m_sysIdRoutine.Quasistatic(direction);

+}

+

+frc2::CommandPtr Drive::SysIdDynamic(frc2::sysid::Direction direction) {

+  return m_sysIdRoutine.Dynamic(direction);

+}

diff --git a/wpilibcExamples/src/main/cpp/examples/SysId/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/SysId/include/Constants.h
new file mode 100644
index 0000000..e01f533
--- /dev/null
+++ b/wpilibcExamples/src/main/cpp/examples/SysId/include/Constants.h
@@ -0,0 +1,81 @@
+// 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 <array>
+#include <numbers>
+
+#include <units/angle.h>
+#include <units/angular_velocity.h>
+#include <units/length.h>
+#include <units/time.h>
+#include <units/voltage.h>
+
+namespace constants {
+namespace drive {
+inline constexpr int kLeftMotor1Port = 0;
+inline constexpr int kLeftMotor2Port = 1;
+inline constexpr int kRightMotor1Port = 2;
+inline constexpr int kRightMotor2Port = 3;
+
+inline constexpr std::array<int, 2> kLeftEncoderPorts = {0, 1};
+inline constexpr std::array<int, 2> kRightEncoderPorts = {2, 3};
+inline constexpr bool kLeftEncoderReversed = false;
+inline constexpr bool kRightEncoderReversed = true;
+
+inline constexpr int kEncoderCpr = 1024;
+inline constexpr units::meter_t kWheelDiameter = 6_in;
+inline constexpr units::meter_t kEncoderDistancePerPulse =
+    (kWheelDiameter * std::numbers::pi) / static_cast<double>(kEncoderCpr);
+}  // namespace drive
+
+namespace shooter {
+
+using kv_unit =
+    units::compound_unit<units::compound_unit<units::volts, units::seconds>,
+                         units::inverse<units::turns>>;
+using kv_unit_t = units::unit_t<kv_unit>;
+
+inline constexpr std::array<int, 2> kEncoderPorts = {4, 5};
+inline constexpr bool kLeftEncoderReversed = false;
+inline constexpr int kEncoderCpr = 1024;
+inline constexpr units::turn_t kEncoderDistancePerPulse =
+    units::turn_t{1.0} / static_cast<double>(kEncoderCpr);
+
+inline constexpr int kShooterMotorPort = 4;
+inline constexpr int kFeederMotorPort = 5;
+
+inline constexpr units::turns_per_second_t kShooterFreeSpeed = 5300_tps;
+inline constexpr units::turns_per_second_t kShooterTargetSpeed = 4000_tps;
+inline constexpr units::turns_per_second_t kShooterTolerance = 50_tps;
+
+inline constexpr double kP = 1.0;
+
+inline constexpr units::volt_t kS = 0.05_V;
+inline constexpr kv_unit_t kV = (12_V) / kShooterFreeSpeed;
+
+inline constexpr double kFeederSpeed = 0.5;
+}  // namespace shooter
+
+namespace intake {
+inline constexpr int kMotorPort = 6;
+inline constexpr std::array<int, 2> kSolenoidPorts = {2, 3};
+}  // namespace intake
+
+namespace storage {
+inline constexpr int kMotorPort = 7;
+inline constexpr int kBallSensorPort = 6;
+}  // namespace storage
+
+namespace autonomous {
+inline constexpr units::second_t kTimeout = 3_s;
+inline constexpr units::meter_t kDriveDistance = 2_m;
+inline constexpr double kDriveSpeed = 0.5;
+}  // namespace autonomous
+
+namespace oi {
+inline constexpr int kDriverControllerPort = 0;
+}  // namespace oi
+}  // namespace constants
diff --git a/wpilibcExamples/src/main/cpp/examples/SysId/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/SysId/include/Robot.h
new file mode 100644
index 0000000..b81adf1
--- /dev/null
+++ b/wpilibcExamples/src/main/cpp/examples/SysId/include/Robot.h
@@ -0,0 +1,35 @@
+// 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 <optional>

+

+#include <frc/TimedRobot.h>

+#include <frc2/command/CommandPtr.h>

+

+#include "SysIdRoutineBot.h"

+

+class Robot : public frc::TimedRobot {

+ public:

+  void RobotInit() override;

+  void RobotPeriodic() override;

+  void DisabledInit() override;

+  void DisabledPeriodic() override;

+  void DisabledExit() override;

+  void AutonomousInit() override;

+  void AutonomousPeriodic() override;

+  void AutonomousExit() override;

+  void TeleopInit() override;

+  void TeleopPeriodic() override;

+  void TeleopExit() override;

+  void TestInit() override;

+  void TestPeriodic() override;

+  void TestExit() override;

+

+ private:

+  std::optional<frc2::CommandPtr> m_autonomousCommand;

+

+  SysIdRoutineBot m_container;

+};

diff --git a/wpilibcExamples/src/main/cpp/examples/SysId/include/SysIdRoutineBot.h b/wpilibcExamples/src/main/cpp/examples/SysId/include/SysIdRoutineBot.h
new file mode 100644
index 0000000..6630abd
--- /dev/null
+++ b/wpilibcExamples/src/main/cpp/examples/SysId/include/SysIdRoutineBot.h
@@ -0,0 +1,24 @@
+// 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 <frc2/command/CommandPtr.h>

+#include <frc2/command/button/CommandXboxController.h>

+

+#include "Constants.h"

+#include "subsystems/Drive.h"

+

+class SysIdRoutineBot {

+ public:

+  SysIdRoutineBot();

+

+  frc2::CommandPtr GetAutonomousCommand();

+

+ private:

+  void ConfigureBindings();

+  frc2::CommandXboxController m_driverController{

+      constants::oi::kDriverControllerPort};

+  Drive m_drive{};

+};

diff --git a/wpilibcExamples/src/main/cpp/examples/SysId/include/subsystems/Drive.h b/wpilibcExamples/src/main/cpp/examples/SysId/include/subsystems/Drive.h
new file mode 100644
index 0000000..61d34f1
--- /dev/null
+++ b/wpilibcExamples/src/main/cpp/examples/SysId/include/subsystems/Drive.h
@@ -0,0 +1,62 @@
+// 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 <functional>
+
+#include <frc/Encoder.h>
+#include <frc/RobotController.h>
+#include <frc/drive/DifferentialDrive.h>
+#include <frc/motorcontrol/PWMSparkMax.h>
+#include <frc2/command/SubsystemBase.h>
+#include <frc2/command/sysid/SysIdRoutine.h>
+
+#include "Constants.h"
+
+class Drive : public frc2::SubsystemBase {
+ public:
+  Drive();
+
+  frc2::CommandPtr ArcadeDriveCommand(std::function<double()> fwd,
+                                      std::function<double()> rot);
+  frc2::CommandPtr SysIdQuasistatic(frc2::sysid::Direction direction);
+  frc2::CommandPtr SysIdDynamic(frc2::sysid::Direction direction);
+
+ private:
+  frc::PWMSparkMax m_leftMotor{constants::drive::kLeftMotor1Port};
+  frc::PWMSparkMax m_rightMotor{constants::drive::kRightMotor1Port};
+  frc::DifferentialDrive m_drive{[this](auto val) { m_leftMotor.Set(val); },
+                                 [this](auto val) { m_rightMotor.Set(val); }};
+
+  frc::Encoder m_leftEncoder{constants::drive::kLeftEncoderPorts[0],
+                             constants::drive::kLeftEncoderPorts[1],
+                             constants::drive::kLeftEncoderReversed};
+
+  frc::Encoder m_rightEncoder{constants::drive::kRightEncoderPorts[0],
+                              constants::drive::kRightEncoderPorts[1],
+                              constants::drive::kRightEncoderReversed};
+
+  frc2::sysid::SysIdRoutine m_sysIdRoutine{
+      frc2::sysid::Config{std::nullopt, std::nullopt, std::nullopt,
+                          std::nullopt},
+      frc2::sysid::Mechanism{
+          [this](units::volt_t driveVoltage) {
+            m_leftMotor.SetVoltage(driveVoltage);
+            m_rightMotor.SetVoltage(driveVoltage);
+          },
+          [this](frc::sysid::SysIdRoutineLog* log) {
+            log->Motor("drive-left")
+                .voltage(m_leftMotor.Get() *
+                         frc::RobotController::GetBatteryVoltage())
+                .position(units::meter_t{m_leftEncoder.GetDistance()})
+                .velocity(units::meters_per_second_t{m_leftEncoder.GetRate()});
+            log->Motor("drive-right")
+                .voltage(m_rightMotor.Get() *
+                         frc::RobotController::GetBatteryVoltage())
+                .position(units::meter_t{m_rightEncoder.GetDistance()})
+                .velocity(units::meters_per_second_t{m_rightEncoder.GetRate()});
+          },
+          this}};
+};
diff --git a/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp
index 4e48d47..f7b3e9c 100644
--- a/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp
@@ -14,12 +14,17 @@
 class Robot : public frc::TimedRobot {
   frc::PWMSparkMax m_leftMotor{0};
   frc::PWMSparkMax m_rightMotor{1};
-  frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor};
+  frc::DifferentialDrive m_robotDrive{
+      [&](double output) { m_leftMotor.Set(output); },
+      [&](double output) { m_rightMotor.Set(output); }};
   frc::Joystick m_leftStick{0};
   frc::Joystick m_rightStick{1};
 
  public:
   void RobotInit() override {
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);
+
     // We need to invert one side of the drivetrain so that positive voltages
     // result in both sides moving forward. Depending on how your robot's
     // gearbox is constructed, you might have to invert the left side instead.
diff --git a/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp
index b8cff32..7c0706e 100644
--- a/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp
@@ -14,11 +14,16 @@
 class Robot : public frc::TimedRobot {
   frc::PWMSparkMax m_leftMotor{0};
   frc::PWMSparkMax m_rightMotor{1};
-  frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor};
+  frc::DifferentialDrive m_robotDrive{
+      [&](double output) { m_leftMotor.Set(output); },
+      [&](double output) { m_rightMotor.Set(output); }};
   frc::XboxController m_driverController{0};
 
  public:
   void RobotInit() override {
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
+    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);
+
     // We need to invert one side of the drivetrain so that positive voltages
     // result in both sides moving forward. Depending on how your robot's
     // gearbox is constructed, you might have to invert the left side instead.
diff --git a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp
index 9d2b5c2..fecaf97 100644
--- a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp
@@ -4,6 +4,11 @@
 
 #include "Robot.h"
 
+Robot::Robot() {
+  wpi::SendableRegistry::AddChild(&m_robotDrive, &m_left);
+  wpi::SendableRegistry::AddChild(&m_robotDrive, &m_right);
+}
+
 void Robot::AutonomousInit() {
   // Set setpoint of the pid controller
   m_pidController.SetSetpoint(kHoldDistance.value());
diff --git a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h
index 4ff2700..696f066 100644
--- a/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h
+++ b/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h
@@ -18,6 +18,7 @@
  */
 class Robot : public frc::TimedRobot {
  public:
+  Robot();
   void AutonomousInit() override;
   void AutonomousPeriodic() override;
 
@@ -31,9 +32,7 @@
 
  private:
   // proportional speed constant
-  // negative because applying positive voltage will bring us closer to the
-  // target
-  static constexpr double kP = -0.001;
+  static constexpr double kP = 0.001;
   // integral speed constant
   static constexpr double kI = 0.0;
   // derivative speed constant
@@ -46,6 +45,8 @@
   frc::Ultrasonic m_ultrasonic{kUltrasonicPingPort, kUltrasonicEchoPort};
   frc::PWMSparkMax m_left{kLeftMotorPort};
   frc::PWMSparkMax m_right{kRightMotorPort};
-  frc::DifferentialDrive m_robotDrive{m_left, m_right};
+  frc::DifferentialDrive m_robotDrive{
+      [&](double output) { m_left.Set(output); },
+      [&](double output) { m_right.Set(output); }};
   frc::PIDController m_pidController{kP, kI, kD};
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/UnitTest/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/UnitTest/include/Constants.h
index 2ad9b07..f736bd3 100644
--- a/wpilibcExamples/src/main/cpp/examples/UnitTest/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/UnitTest/include/Constants.h
@@ -14,13 +14,13 @@
  */
 
 namespace IntakeConstants {
-constexpr int kMotorPort = 1;
+inline constexpr int kMotorPort = 1;
 
-constexpr int kPistonFwdChannel = 0;
-constexpr int kPistonRevChannel = 1;
-constexpr double kIntakeSpeed = 0.5;
+inline constexpr int kPistonFwdChannel = 0;
+inline constexpr int kPistonRevChannel = 1;
+inline constexpr double kIntakeSpeed = 0.5;
 }  // namespace IntakeConstants
 
 namespace OperatorConstants {
-constexpr int kJoystickIndex = 0;
+inline constexpr int kJoystickIndex = 0;
 }  // namespace OperatorConstants
diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp
index bcec018..25c520c 100644
--- a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp
@@ -15,6 +15,9 @@
 // The XRP has onboard encoders that are hardcoded
 // to use DIO pins 4/5 and 6/7 for the left and right
 Drivetrain::Drivetrain() {
+  wpi::SendableRegistry::AddChild(&m_drive, &m_leftMotor);
+  wpi::SendableRegistry::AddChild(&m_drive, &m_rightMotor);
+
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
   // gearbox is constructed, you might have to invert the left side instead.
diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Constants.h
index e5cee33..dddb741 100644
--- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Constants.h
@@ -14,6 +14,6 @@
  */
 
 namespace DriveConstants {
-constexpr double kCountsPerRevolution = 1440.0;
-constexpr double kWheelDiameterInch = 2.75;
+inline constexpr double kCountsPerRevolution = 1440.0;
+inline constexpr double kWheelDiameterInch = 2.75;
 }  // namespace DriveConstants
diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.h
index e665601..c2a2ef3 100644
--- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.h
@@ -118,7 +118,9 @@
   frc::Encoder m_leftEncoder{4, 5};
   frc::Encoder m_rightEncoder{6, 7};
 
-  frc::DifferentialDrive m_drive{m_leftMotor, m_rightMotor};
+  frc::DifferentialDrive m_drive{
+      [&](double output) { m_leftMotor.Set(output); },
+      [&](double output) { m_rightMotor.Set(output); }};
 
   frc::XRPGyro m_gyro;
   frc::BuiltInAccelerometer m_accelerometer;
diff --git a/wpilibcExamples/src/main/cpp/examples/examples.json b/wpilibcExamples/src/main/cpp/examples/examples.json
index 8032909..486e2ec 100644
--- a/wpilibcExamples/src/main/cpp/examples/examples.json
+++ b/wpilibcExamples/src/main/cpp/examples/examples.json
@@ -927,5 +927,17 @@
     "foldername": "FlywheelBangBangController",
     "gradlebase": "cpp",
     "commandversion": 2
+  },
+  {
+    "name": "SysIdRoutine",
+    "description": "A sample command-based robot demonstrating use of the SysIdRoutine command factory",
+    "tags": [
+      "SysId",
+      "Command-based",
+      "DataLog"
+    ],
+    "foldername": "SysId",
+    "gradlebase": "cpp",
+    "commandversion": 2
   }
 ]
diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/include/Constants.h b/wpilibcExamples/src/main/cpp/templates/commandbased/include/Constants.h
index 963b31c..87dd5b9 100644
--- a/wpilibcExamples/src/main/cpp/templates/commandbased/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/templates/commandbased/include/Constants.h
@@ -16,6 +16,6 @@
 
 namespace OperatorConstants {
 
-constexpr int kDriverControllerPort = 0;
+inline constexpr int kDriverControllerPort = 0;
 
 }  // namespace OperatorConstants
diff --git a/wpilibcExamples/src/test/cpp/examples/UltrasonicPID/cpp/UltrasonicPIDTest.cpp b/wpilibcExamples/src/test/cpp/examples/UltrasonicPID/cpp/UltrasonicPIDTest.cpp
index a970a3a..5cfcbe8 100644
--- a/wpilibcExamples/src/test/cpp/examples/UltrasonicPID/cpp/UltrasonicPIDTest.cpp
+++ b/wpilibcExamples/src/test/cpp/examples/UltrasonicPID/cpp/UltrasonicPIDTest.cpp
@@ -57,7 +57,7 @@
     m_driveSim.Update(20_ms);
 
     auto startingDistance = units::meter_t{GetParam()};
-    m_distance = startingDistance - m_driveSim.GetLeftPosition();
+    m_distance = m_driveSim.GetLeftPosition() - startingDistance;
 
     m_ultrasonicSim.SetRange(m_distance);
   }
@@ -99,8 +99,7 @@
   }
 
   {
-    // advance 100 timesteps
-    frc::sim::StepTiming(2_s);
+    frc::sim::StepTiming(5_s);
 
     EXPECT_NEAR(Robot::kHoldDistance.value(), m_distance.value(), 10.0);
   }