Squashed 'third_party/allwpilib/' changes from e473a00f97..e4b91005cf

e4b91005cf [examples] Update SwerveModule constructor doc (NFC) (#4042)
a260bfd83b [examples] Remove "this" keyword from SwerveModule (#4043)
18e262a100 [examples] Fix multiple doc typos in SwerveControllerCommand example (NFC) (#4044)
4bd1f526ab [wpilibc] Prevent StopMotor from terminating robot during MotorSafety check (#4038)
27847d7eb2 [sim] Expose GUI control functions via HAL_RegisterExtension (#4034)
b2a8d3f0f3 [wpilibc] Add mechanism to reset MotorSafety list (#4037)
49adac9564 [wpilib] Check for signedness in ArcadeDriveIK() (#4028)
a19d1133b1 [wpiutil] libuv: Fix sign compare warnings in gcc 11.2 (#4031)
dde91717e4 [build] cmake: Add ability to customize target warnings (#4032)
e9050afd67 [sim] Update sim match time to match real robot (#4024)
165d2837cf [wpilib] Preferences: Set Persistent in Init methods (#4025)
ac7549edca [glass] Fix snprintf truncation warning (#4029)
4d96bc72e0 [wpilibj] Fix typos in error messages for non-null assertions (#4014)
3411eee20f [hal] Replace hardcoded sim array sizes with constants (#4015)
74de97eeca [wpilibc] Add mechanism to reset various global structures (#4007)
4e3cc25012 [examples] Fix periodic function rate comment (NFC) (#4013)
90c1db393e [sim] Add exported functions to control the sim GUI (#3995)
2f43274aa4 [wpilibj] MechanismRoot2d: Add flush to setPosition (#4011)
aeca09db09 [glass] Support remapping of Enter key (#3994)
c107f22c67 [sim] Sim GUI: don't force-show Timing and Other Devices (#4001)
68fe51e8da [wpigui] Update PFD to latest, fix kdialog multiselect (#4005)
8d08d67cf1 [wpigui] PFD: Add console warning if file chooser unavailable (#4003)
4f1782f66e [wpilibc] Only call HAL_Report when initializing SmartDashboard (#4006)
3f77725cd3 Remove uses of iostream (#4004)
5635f33a32 [glass] Increase plot depth to 20K points (#3993)
bca4b7111b [glass] Fix PlotSeries::SetSource() (#3991)
6a6366b0d6 [commands] Add until() as alias for withInterrupt() (#3981)
16bf2c70c5 [wpilib] Fix joystick out of range error messages (#3988)
4b3edb742c [wpilib] Fix ADIS16448 IMU default constructor not working in Java (#3989)
fcf23fc9e9 [hal] Fix potential gamedata out of bounds read (#3983)
af5ef510c5 [wpilibc] Fix REV PH pulse duration units (#3982)
05401e2b81 [wpilib] Write REV PH firmware version to roboRIO to display on driver station (#3977)
9fde0110b6 Update to 2022 v4.0 image (#3944)
b03f8ddb2e [examples] fix incorrect variable in Arm Simulation Pref (#3980)
a26df2a022 [examples] Update ArmSimulation example to use Preferences (#3976)
d68d6674e8 [examples] Armbot: rename kCos to kG (#3975)
a8f0f6bb90 [wpilibj] Fix ADIS16448 getRate to return rate instead of angle (#3974)
dd9c92d5bf [build] Remove debug info from examples (#3971)
84df14dd70 [rtns] Fix icons (#3972)
560094ad92 [examples] Correct Mecanum example axes (#3955)
7ea1be9c01 [wpilibc] Fix typo in hardware version for REV PDH (#3969)
700f13bffd [wpilibj] Make methods public for Java REV PDH (#3970)
b6aa7c1aa9 [wpilibj] Make methods public for Java REVPH (#3968)
eb4d183e48 [wpimath] Fix clang-tidy bugprone-integer-division warning (#3966)
77e4e81e1e [wpilib] Add Field widget to BuiltInWidgets in shuffleboard (#3961)
88f5cb6eb0 [build] Publish PDBs with C++ tools (#3960)
efae552f3e [wpimath] Remove DifferentialDriveKinematics include from odometry (#3958)
46b277421a [glass] Update Speed Controller Type name for 2022 WPILib (#3952)
42908126b9 [wpilib] Add DCMotorSim (#3910)
a467392cbd [wpiutil] StackTrace: Add ability to override default implementation (#3951)
78d0bcf49d [templates] Add SimulationInit()/SimulationPeriodic() to robot templates (#3943)
02a0ced9b0 [wpilib] MecanumDrive: update docs for axis to match implementation (NFC) (#3942)
4ccfe1c9f2 [wpilib] Added docs clarification on units for drive class WheelSpeeds (NFC) (#3939)
830c0c5c2f [wpilib] MechanismLigament2d: Add getters for color and line weight (#3947)
5548a37465 [wpilib] PowerDistribution: Add module type getter (#3948)
2f9a600de2 [hal] Fix PCM one shot (#3949)
559db11a20 [myRobot] Skip deploying debug libraries for myRobot deploys (#3950)
76c78e295b [examples] Reorder SwerveModules in SwerveControllerCommand example odometry update (#3934)
debbd5ff4b [wpilib] Improve PowerDistribution docs (NFC) (#3925)
841174f302 [commands] Change command vendordep JSON version number to 1.0.0 (#3938)
8c55844f91 [wpilib] Remove comment about Mecanum right side inverted (NFC) (#3929)
0b990bf0f5 [hal] Fix PCM sticky faults clear function crashing (#3932)
104d7e2abc [hal] Don't throw exceptions in PCM JNI (#3933)
5ba69e1af1 [examples] Updated type in Java SwerveModule (#3928)
f3a0b5c7d7 [wpimath] Fix Java SimpleMotorFeedforward Docs (NFC) (#3926)
7f4265facc [wpimath] Add LinearFilter::FiniteDifference() (#3900)
63d1fb3bed [wpiutil] Modify fmt to not throw on write failure (#3919)
36af6d25a5 [wpimath] Fix input vector in pose estimator docs (NFC) (#3923)
8f387f7255 [wpilibj] Switch ControlWord mutex to actual reentrant mutex (#3922)
792e735e08 [wpimath] Move TrajectoryGenerator::SetErrorHandler definition to .cpp (#3920)
3b76de83eb [commands] Fix ProfiledPIDCommand use-after-free (#3904)
ad9f738cfa [fieldimages] Fix maven publishing (#3897)
49455199e5 [examples] Use left/rightGroup.Get() for simulator inputs to fix inversions (#3908)
64426502ea [wpimath] Fix arm -> flywheel typo (NFC) (#3911)
8cc112d196 [wpiutil] Fix wpi::array for move-only types (#3917)
e78cd49861 [build] Upgrade Java formatter plugins (#3894)
cfb4f756d6 [build] Upgrade to shadow 7.1.2 (#3893)
ba0908216c [wpimath] Fix crash in KF latency compensator (#3888)
a3a0334fad [build] cmake: Move fieldImages to WITH_GUI (#3885)
cf7460c3a8 [fieldImages] Add 2022 field (#3883)
db0fbb6448 [wpimath] Fix LQR matrix constructor overload for Q, R, and N (#3884)
8ac45f20bb [commands] Update Command documentation (NFC) (#3881)
b3707cca0b [wpiutil] Upgrade to fmt 8.1.1 (#3879)
a69ee3ece9 [wpimath] Const-qualify Twist2d scalar multiply (#3882)
750d9a30c9 [examples] Fix Eigen out of range error when running example (#3877)
41c5b2b5ac [rtns] Add cmake build (#3866)
6cf3f9b28e [build] Upgrade to Gradle 7.3.3 (#3878)
269cf03472 [examples] Add communication examples (e.g. arduino) (#2500)
5ccfc4adbd [oldcommands] Deprecate PIDWrappers, since they use deprecated interfaces (#3868)
b6f44f98be [hal] Add warning about onboard I2C (#3871)
0dca57e9ec [templates] romieducational: Invert drivetrain and disable motor safety (#3869)
22c4da152e [wpilib] Add GetRate() to ADIS classes (#3864)
05d66f862d [templates] Change the template ordering to put command based first (#3863)
b09f5b2cf2 [wpilibc] Add virtual dtor for LinearSystemSim (#3861)
a2510aaa0e [wpilib] Make ADIS IMU classes unit-safe (#3860)
947f589916 [wpilibc] Rename ADIS_16470_IMU.cpp to match class name (#3859)
bbd8980a20 [myRobot] Fix cameraserver library order (#3858)
831052f118 [wpilib] Add simulation support to ADIS classes (#3857)
c137569f91 [wpilib] Throw exception if the REV Pneumatic Hub firmware version is older than 22.0.0 (#3853)
dae61226fa Fix Maven Artifacts readme (#3856)
3ad4594a88 Update Maven artifacts readme for 2022 (#3855)
112acb9a62 [wpilibc] Move ADIS IMU constants to inside class (#3852)
ecee224e81 [wpilib] Allow SendableCameraWrappers to take arbitrary URLs (#3850)
a3645dea34 LICENSE: Bump year range to include 2022 (#3854)
7c09f44898 [wpilib] Use PSI for compressor config and sensor reading (#3847)
f401ea9aae [wpigui] Remove wpiutil linkage (#3851)
bf8517f1e6 [wpimath] TimeInterpolatableBufferTest: Fix lint warnings (#3849)
528087e308 [hal] Use enums with fixed underlying type in clang C (#3297)
1f59ff72f9 [wpilib] Add ADIS IMUs (#3777)
315be873c4 [wpimath] Add TimeInterpolatableBuffer (#2695)
b8d019cdb4 [wpilib] Rename NormalizeWheelSpeeds to DesaturateWheelSpeeds (#3791)
102f23bbdb [wpilibj] DriverStation: Set thread interrupted state (#3846)
b85c24a79c [wpilib] Add warning about onboard I2C (#3842)
eee29daaf9 [newCommands] Trigger: Allow override of debounce type (#3845)
aa9dfabde2 [wpimath] Move debouncer to filters (#3838)
5999a26fba [wpiutil] Add GetSystemTime() (#3840)
1e82595ffb [examples] Fix arcade inversions (#3841)
e373fa476b [wpiutil] Add disableMockTime to JNI (#3839)
dceb5364f4 [examples] Ensure right side motors are inverted (#3836)
baacbc8e24 [wpilib] Tachometer: Add function to return RPS (#3833)
84b15f0883 [templates] Add Java Romi Educational template (#3837)
c0da9d2d35 [examples] Invert Right Motor in Romi Java examples (#3828)
0fe0be2733 [build] Change project year to intellisense (#3835)
eafa947338 [wpimath] Make copies of trajectory constraint arguments (#3832)
9d13ae8d01 [wpilib] Add notes for Servo get that it only returns cmd (NFC) (#3820)
2a64e4bae5 [wpimath] Give drivetrain a more realistic width in TrajectoryJsonTest.java (#3822)
c3fd20db59 [wpilib] Fix trajectory sampling in DifferentialDriveSim test (#3821)
6f91f37cd0 [examples] Fix SwerveControllerCommand order of Module States (#3815)
5158730b81 [wpigui] Upgrade to imgui 1.86, GLFW 3.3.6 (#3817)
2ad2d2ca96 [wpiutil] MulticastServiceResolver: Fix C array returning functions (#3816)
b5fd29774f [wpilibj] Trigger: implement BooleanSupplier interface (#3811)
9f8f330e96 [wpilib] Fix Mecanum and SwerveControllerCommand when desired rotation passed (#3808)
1ad3b1b333 [hal] Don't copy byte to where null terminator goes (#3807)
dfc24425c3 [build] Fix gazebo gradle IDE warnings (#3806)
c02577bb51 [glass] Configure delay loading for windows camera server support (#3803)
c9e6a96a61 [wpilib] Document range of Servo angle (NFC) (#3796)
9778626f34 [wpilib, hal] Add support for getting faults and versions from power distribution (#3794)
34b2d0dae1 [wpilib, hal] High Level REV PH changes (#3792)
59a7528fd6 [cscore] Fix crash when usbcamera is deleted before message pump thread fully starts (#3804)
11d9859ef1 [build] Update plugins to remove log4j vulnerabilities (#3805)
e44ed752ad [glass] Fix CollapsingHeader in Encoder, PCM, and DeviceTree (#3797)
52b2dd5b89 [build] Bump native utils to remove log4j (#3802)
c46636f218 [wpilib] Improve new counter classes documentation (NFC) (#3801)
dc531462e1 [build] Update to gradle 7.3.2 (#3800)
92ba98621c [wpimath] Add helper variable templates for units type traits (#3790)
d41d051f1b [wpilibc] Fix Mecanum & Swerve ControllerCommand lambda capture (#3795)
c5ae0effac OtherVersions.md: Add one missing case of useLocal (#3788)
b3974c6ed3 [wpimath] Upgrade to Drake v0.37.0 (#3786)
589a00e379 [wpilibc] Start DriverStation thread from RobotBase (#3785)
8d9836ca02 [wpilib] Improve curvature drive documentation (NFC) (#3783)
8b5bf8632e [myRobot] Add wpimath and wpiutil JNI (#3784)
1846114491 [examples] Update references from characterization to SysId (NFC) (#3782)
2c461c794e [build] Update to gradle 7.3 (#3778)
109363daa4 [hal] Add remaining driver functions for REVPH (#3776)
41d26bee8d [hal] Refactor REV PDH (#3775)
7269a170fb Upgrade maven deps to latest versions and fix new linter errors (#3772)
441f2ed9b0 [build] actions: use fixed image versions instead latest (#3761)
15275433d4 [examples] Fix duplicate port allocations in C++ SwerveBot/SwerveDrivePoseEstimator/RomiReference (#3773)
1ac02d2f58 [examples] Fix drive Joystick axes in several examples (#3769)
8ee6257e92 [wpilib] DifferentialDrivetrainSim.KitbotMotor: Add NEO and Falcon 500 (#3762)
d81ef2bc5c [wpilib] Fix deadlocks in Mechanism2d et al. (#3770)
acb64dff97 [wpimath] Make RamseteController::Calculate() more concise (#3763)
3f6cf76a8c [hal] Refactor REV PH CAN frames (#3756)
3ef2dab465 [wpilib] DutyCycleEncoder: add setting of duty cycle range (#3759)
a5a56dd067 Readme: Add Visual Studio 2022 (#3760)
04957a6d30 [wpimath] Fix units of RamseteController's b and zeta (#3757)
5da54888f8 [glass] Upgrade imgui to 0.85, implot to HEAD, glfw to 3.3.5 (#3754)
6c93365b0f [wpiutil] MulticastService cleanup (#3750)
1c4a8bfb66 [cscore] Cleanup Windows USB camera impl (#3751)
d51a1d3b3d [rtns] Fix icon (#3749)
aced2e7da6 Add roboRIO Team Number Setter tool (#3744)
fa1ceca83a [wpilibj] Use DS cache for iterative robot control word cache (#3748)
0ea05d34e6 [build] Update to gradle 7.2 (#3746)
09db4f672b [build] Update to native utils 2022.6.1 (#3745)
4ba80a3a8c [wpigui] Don't recursively render frames in size callback (#3743)
ae208d2b17 [wpiutil] StringExtras: Add substr() (#3742)
6f51cb3b98 [wpiutil] MulticastResolver: make event manual reset, change to multiple read (#3736)
f6159ee1a2 [glass] Fix Drive widget handling of negative rotation (#3739)
7f401ae895 [build] Update NI libraries to 2022.2.3 (#3738)
0587b7043a [glass] Use JSON files for storage instead of imgui ini
0bbf51d566 [wpigui] Change maximized to bool
92c6eae6b0 [wpigui] PFD: Add explicit to constructors
141354cd79 [wpigui] Add hooks for custom load/save settings
f6e9fc7d71 [wpiutil] Handle multicast service collision on linux (#3734)
d8418be7d1 [glass, outlineviewer] Return 0 from WinMain (#3735)
82066946e5 [wpiutil] Add mDNS resolver and announcer (#3733)
4b1defc8d8 [wpilib] Remove automatic PD type from module type enum (#3732)
da90c1cd2c [wpilib] Add bang-bang controller (#3676)
3aa54fa027 [wpilib] Add new counter implementations (#2447)
b156db400d [hal, wpilib] Incorporate pneumatic control type into wpilibc/j (#3728)
9aba2b7583 [oldCommands] Add wrappers for WPILib objects to work with old PID Controller (#3710)
a9931223f0 [hal] Add REV PH faults (#3729)
aacf9442e4 [wpimath] Fix units typo in LinearSystemId source comment (#3730)
7db10ecf00 [wpilibc] Make SPI destructor virtual since SPI contains virtual functions (#3727)
a0a5b2aea5 [wpimath] Upgrade to EJML 0.41 (#3726)
eb835598a4 [hal] Add HAL functions for compressor config modes on REV PH (#3724)
f0ab6df5b6 [wpimath] Upgrade to Drake v0.36.0 (#3722)
075144faa3 [docs] Parse files without extensions with Doxygen (#3721)
32468a40cb [hal] Remove use of getDmaDescriptor from autospi (#3717)
38611e9dd7 [hal] Fix REVPH Analog Pressure channel selection (#3716)
4d78def31e [wpilib] Add DeadbandElimination forwarding to PWMMotorController (#3714)
3be0c1217a [wpilibcExamples] Make GearsBot use idiomatic C++ (#3711)
42d3a50aa2 [hal] Check error codes during serial port initialization (#3712)
52f1464029 Add project with field images and their json config files (#3668)
68ce62e2e9 [hal] Add autodetect for power modules (#3706)
3dd41c0d37 [wpilib] Don't print PD errors for LiveWindow reads (#3708)
7699a1f827 [hal] Fix sim not working with automatic PD type and default module (#3707)

Change-Id: I6b0b8fa8b2d2a24071240f624db9ec6d127f6648
git-subtree-dir: third_party/allwpilib
git-subtree-split: e4b91005cf69161f1cb3d934f6526232e6b9169e
Signed-off-by: Austin Schuh <austin.linux@gmail.com>
diff --git a/wpilibcExamples/build.gradle b/wpilibcExamples/build.gradle
index 975e90a..7561ed5 100644
--- a/wpilibcExamples/build.gradle
+++ b/wpilibcExamples/build.gradle
@@ -39,6 +39,12 @@
     cppCompiler.args.add('-Werror=deprecated-declarations')
 }
 
+nativeUtils.platformConfigs.named(nativeUtils.wpi.platforms.windowsx64).configure {
+    linker.args.remove('/DEBUG:FULL')
+    cppCompiler.debugArgs.remove('/Zi')
+    cCompiler.debugArgs.remove('/Zi')
+}
+
 ext {
     sharedCvConfigs = examplesMap + templatesMap + [commands: []]
     staticCvConfigs = [:]
diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp
index abe79f4..e346e41 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp
@@ -18,9 +18,16 @@
   frc::Joystick m_stick{0};
 
  public:
+  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
+    // gearbox is constructed, you might have to invert the left side instead.
+    m_rightMotor.SetInverted(true);
+  }
+
   void TeleopPeriodic() override {
     // Drive with arcade style
-    m_robotDrive.ArcadeDrive(m_stick.GetY(), m_stick.GetX());
+    m_robotDrive.ArcadeDrive(-m_stick.GetY(), m_stick.GetX());
   }
 };
 
diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp
index 644e35f..7f497b3 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp
@@ -18,11 +18,18 @@
   frc::XboxController m_driverController{0};
 
  public:
+  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
+    // gearbox is constructed, you might have to invert the left side instead.
+    m_rightMotor.SetInverted(true);
+  }
+
   void TeleopPeriodic() override {
     // Drive with split arcade style
     // That means that the Y axis of the left stick moves forward
     // and backward, and the X of the right stick turns left and right.
-    m_robotDrive.ArcadeDrive(m_driverController.GetLeftY(),
+    m_robotDrive.ArcadeDrive(-m_driverController.GetLeftY(),
                              m_driverController.GetRightX());
   }
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/Robot.cpp
index 2803c5c..d3a106b 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/Robot.cpp
@@ -10,7 +10,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp
index 48310da..158945e 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp
@@ -17,7 +17,7 @@
   // Set up default drive command
   m_drive.SetDefaultCommand(frc2::RunCommand(
       [this] {
-        m_drive.ArcadeDrive(m_driverController.GetLeftY(),
+        m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
                             m_driverController.GetRightX());
       },
       {&m_drive}));
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/ArmSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/ArmSubsystem.cpp
index 8618aaa..c5fb3b2 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/ArmSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/ArmSubsystem.cpp
@@ -15,7 +15,7 @@
               kP, 0, 0, {kMaxVelocity, kMaxAcceleration})),
       m_motor(kMotorPort),
       m_encoder(kEncoderPorts[0], kEncoderPorts[1]),
-      m_feedforward(kS, kCos, kV, kA) {
+      m_feedforward(kS, kG, kV, kA) {
   m_encoder.SetDistancePerPulse(kEncoderDistancePerPulse.value());
   // Start arm in neutral position
   SetGoal(State{kArmOffset, 0_rad_per_s});
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 5ba38b8..aeeac3d 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/DriveSubsystem.cpp
@@ -16,6 +16,10 @@
   // 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);
 }
 
 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 16a4e00..bd432ee 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/Constants.h
@@ -46,7 +46,7 @@
 // These are fake gains; in actuality these must be determined individually for
 // each robot
 constexpr auto kS = 1_V;
-constexpr auto kCos = 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;
 
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/Robot.cpp
index 8cd7b02..c7eab48 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/Robot.cpp
@@ -10,7 +10,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp
index b5a4420..1f6a138 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp
@@ -17,7 +17,7 @@
   // Set up default drive command
   m_drive.SetDefaultCommand(frc2::RunCommand(
       [this] {
-        m_drive.ArcadeDrive(m_driverController.GetLeftY(),
+        m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
                             m_driverController.GetRightX());
       },
       {&m_drive}));
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/ArmSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/ArmSubsystem.cpp
index f80970a..7557b5a 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/ArmSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/ArmSubsystem.cpp
@@ -13,7 +13,7 @@
     : frc2::TrapezoidProfileSubsystem<units::radians>(
           {kMaxVelocity, kMaxAcceleration}, kArmOffset),
       m_motor(kMotorPort),
-      m_feedforward(kS, kCos, kV, kA) {
+      m_feedforward(kS, kG, kV, kA) {
   m_motor.SetPID(kP, 0, 0);
 }
 
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 03d3415..fac0df9 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/DriveSubsystem.cpp
@@ -16,6 +16,10 @@
   // 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);
 }
 
 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 16a4e00..bd432ee 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/Constants.h
@@ -46,7 +46,7 @@
 // These are fake gains; in actuality these must be determined individually for
 // each robot
 constexpr auto kS = 1_V;
-constexpr auto kCos = 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;
 
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp
index b8b8368..330ddc4 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp
@@ -4,6 +4,7 @@
 
 #include <frc/Encoder.h>
 #include <frc/Joystick.h>
+#include <frc/Preferences.h>
 #include <frc/RobotController.h>
 #include <frc/TimedRobot.h>
 #include <frc/controller/PIDController.h>
@@ -33,8 +34,13 @@
   static constexpr int kEncoderBChannel = 1;
   static constexpr int kJoystickPort = 0;
 
+  static constexpr std::string_view kArmPositionKey = "ArmPosition";
+  static constexpr std::string_view kArmPKey = "ArmP";
+
   // The P gain for the PID controller that drives this arm.
-  static constexpr double kArmKp = 50.0;
+  double kArmKp = 50.0;
+
+  units::degree_t armPosition = 75.0_deg;
 
   // distance per pulse = (angle per revolution) / (pulses per revolution)
   //  = (2 * PI rads) / (4096 pulses)
@@ -81,6 +87,15 @@
 
     // Put Mechanism 2d to SmartDashboard
     frc::SmartDashboard::PutData("Arm Sim", &m_mech2d);
+
+    // Set the Arm position setpoint and P constant to Preferences if the keys
+    // don't already exist
+    if (!frc::Preferences::ContainsKey(kArmPositionKey)) {
+      frc::Preferences::SetDouble(kArmPositionKey, armPosition.value());
+    }
+    if (!frc::Preferences::ContainsKey(kArmPKey)) {
+      frc::Preferences::SetDouble(kArmPKey, kArmKp);
+    }
   }
 
   void SimulationPeriodic() override {
@@ -103,12 +118,22 @@
     m_arm->SetAngle(m_armSim.GetAngle());
   }
 
+  void TeleopInit() override {
+    // Read Preferences for Arm setpoint and kP on entering Teleop
+    armPosition = units::degree_t(
+        frc::Preferences::GetDouble(kArmPositionKey, armPosition.value()));
+    if (kArmKp != frc::Preferences::GetDouble(kArmPKey, kArmKp)) {
+      kArmKp = frc::Preferences::GetDouble(kArmPKey, kArmKp);
+      m_controller.SetP(kArmKp);
+    }
+  }
+
   void TeleopPeriodic() override {
     if (m_joystick.GetTrigger()) {
-      // Here, we run PID control like normal, with a constant setpoint of 75
-      // degrees.
+      // Here, we run PID control like normal, with a setpoint read from
+      // preferences in degrees.
       double pidOutput = m_controller.Calculate(
-          m_encoder.GetDistance(), (units::radian_t(75_deg)).value());
+          m_encoder.GetDistance(), (units::radian_t(armPosition).value()));
       m_motor.SetVoltage(units::volt_t(pidOutput));
     } else {
       // Otherwise, we disable the motor.
diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h
index a4caff4..4697938 100644
--- a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h
+++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.h
@@ -19,6 +19,6 @@
     return frc::Pose2d(estimatedRobotPose.X() + units::meter_t(randVec(0)),
                        estimatedRobotPose.Y() + units::meter_t(randVec(1)),
                        estimatedRobotPose.Rotation() +
-                           frc::Rotation2d(units::radian_t(randVec(3))));
+                           frc::Rotation2d(units::radian_t(randVec(2))));
   }
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/cpp/Robot.cpp
new file mode 100644
index 0000000..037fb1d
--- /dev/null
+++ b/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/cpp/Robot.cpp
@@ -0,0 +1,46 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <frc/DigitalOutput.h>
+#include <frc/DriverStation.h>
+#include <frc/TimedRobot.h>
+
+/**
+ * This is a sample program demonstrating how to communicate to a light
+ * controller from the robot code using the roboRIO's DIO ports.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  void RobotPeriodic() override {
+    // pull alliance port high if on red alliance, pull low if on blue alliance
+    m_allianceOutput.Set(frc::DriverStation::GetAlliance() ==
+                         frc::DriverStation::kRed);
+
+    // pull enabled port high if enabled, low if disabled
+    m_enabledOutput.Set(frc::DriverStation::IsEnabled());
+
+    // pull auto port high if in autonomous, low if in teleop (or disabled)
+    m_autonomousOutput.Set(frc::DriverStation::IsAutonomous());
+
+    // pull alert port high if match time remaining is between 30 and 25 seconds
+    auto matchTime = frc::DriverStation::GetMatchTime();
+    m_alertOutput.Set(matchTime <= 30 && matchTime >= 25);
+  }
+
+ private:
+  // define ports for communication with light controller
+  static constexpr int kAlliancePort = 0;
+  static constexpr int kEnabledPort = 1;
+  static constexpr int kAutonomousPort = 2;
+  static constexpr int kAlertPort = 3;
+
+  frc::DigitalOutput m_allianceOutput{kAlliancePort};
+  frc::DigitalOutput m_enabledOutput{kEnabledPort};
+  frc::DigitalOutput m_autonomousOutput{kAutonomousPort};
+  frc::DigitalOutput m_alertOutput{kAlertPort};
+};
+
+int main() {
+  return frc::StartRobot<Robot>();
+}
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp
index 8cd7b02..c7eab48 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp
@@ -10,7 +10,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
index fb879fe..bc940cd 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
@@ -18,7 +18,7 @@
   // Set up default drive command
   m_drive.SetDefaultCommand(frc2::RunCommand(
       [this] {
-        m_drive.ArcadeDrive(m_driverController.GetLeftY(),
+        m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
                             m_driverController.GetRightX());
       },
       {&m_drive}));
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h
index 92f82ba..6644c08 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.h
@@ -28,9 +28,8 @@
 
 // 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 RobotPy Characterization
-// Toolsuite provides a convenient tool for obtaining these values for your
-// robot.
+// 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;
diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/Robot.cpp
index 8cd7b02..c7eab48 100644
--- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/Robot.cpp
@@ -10,7 +10,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp
index b781422..c459739 100644
--- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp
@@ -16,7 +16,7 @@
   // Set up default drive command
   m_drive.SetDefaultCommand(frc2::RunCommand(
       [this] {
-        m_drive.ArcadeDrive(m_driverController.GetLeftY(),
+        m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
                             m_driverController.GetRightX());
       },
       {&m_drive}));
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/Robot.cpp
index 8cd7b02..c7eab48 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/Robot.cpp
@@ -10,7 +10,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/RobotContainer.cpp
index 3ac0f75..37eb460 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/RobotContainer.cpp
@@ -16,7 +16,7 @@
 #include "commands/TankDrive.h"
 
 RobotContainer::RobotContainer()
-    : m_autonomousCommand(&m_claw, &m_wrist, &m_elevator, &m_drivetrain) {
+    : m_autonomousCommand(m_claw, m_wrist, m_elevator, m_drivetrain) {
   frc::SmartDashboard::PutData(&m_drivetrain);
   frc::SmartDashboard::PutData(&m_elevator);
   frc::SmartDashboard::PutData(&m_wrist);
@@ -24,7 +24,7 @@
 
   m_drivetrain.SetDefaultCommand(TankDrive([this] { return m_joy.GetLeftY(); },
                                            [this] { return m_joy.GetRightY(); },
-                                           &m_drivetrain));
+                                           m_drivetrain));
 
   // Configure the button bindings
   ConfigureButtonBindings();
@@ -33,19 +33,19 @@
 void RobotContainer::ConfigureButtonBindings() {
   // Configure your button bindings here
   frc2::JoystickButton(&m_joy, 5).WhenPressed(
-      SetElevatorSetpoint(0.25, &m_elevator));
-  frc2::JoystickButton(&m_joy, 6).WhenPressed(CloseClaw(&m_claw));
+      SetElevatorSetpoint(0.25, m_elevator));
+  frc2::JoystickButton(&m_joy, 6).WhenPressed(CloseClaw(m_claw));
   frc2::JoystickButton(&m_joy, 7).WhenPressed(
-      SetElevatorSetpoint(0.0, &m_elevator));
-  frc2::JoystickButton(&m_joy, 8).WhenPressed(OpenClaw(&m_claw));
+      SetElevatorSetpoint(0.0, m_elevator));
+  frc2::JoystickButton(&m_joy, 8).WhenPressed(OpenClaw(m_claw));
   frc2::JoystickButton(&m_joy, 9).WhenPressed(
-      Autonomous(&m_claw, &m_wrist, &m_elevator, &m_drivetrain));
+      Autonomous(m_claw, m_wrist, m_elevator, m_drivetrain));
   frc2::JoystickButton(&m_joy, 10)
-      .WhenPressed(Pickup(&m_claw, &m_wrist, &m_elevator));
+      .WhenPressed(Pickup(m_claw, m_wrist, m_elevator));
   frc2::JoystickButton(&m_joy, 11)
-      .WhenPressed(Place(&m_claw, &m_wrist, &m_elevator));
+      .WhenPressed(Place(m_claw, m_wrist, m_elevator));
   frc2::JoystickButton(&m_joy, 12)
-      .WhenPressed(PrepareToPickup(&m_claw, &m_wrist, &m_elevator));
+      .WhenPressed(PrepareToPickup(m_claw, m_wrist, m_elevator));
 }
 
 frc2::Command* RobotContainer::GetAutonomousCommand() {
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Autonomous.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Autonomous.cpp
index 23ccfff..d6434d1 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Autonomous.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Autonomous.cpp
@@ -14,8 +14,8 @@
 #include "commands/SetDistanceToBox.h"
 #include "commands/SetWristSetpoint.h"
 
-Autonomous::Autonomous(Claw* claw, Wrist* wrist, Elevator* elevator,
-                       Drivetrain* drivetrain) {
+Autonomous::Autonomous(Claw& claw, Wrist& wrist, Elevator& elevator,
+                       Drivetrain& drivetrain) {
   SetName("Autonomous");
   AddCommands(
       // clang-format off
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/CloseClaw.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/CloseClaw.cpp
index d10c310..75884a2 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/CloseClaw.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/CloseClaw.cpp
@@ -6,7 +6,7 @@
 
 #include "Robot.h"
 
-CloseClaw::CloseClaw(Claw* claw) : m_claw(claw) {
+CloseClaw::CloseClaw(Claw& claw) : m_claw(&claw) {
   SetName("CloseClaw");
   AddRequirements({m_claw});
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/DriveStraight.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/DriveStraight.cpp
index 60408db..d3e85bd 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/DriveStraight.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/DriveStraight.cpp
@@ -8,13 +8,13 @@
 
 #include "Robot.h"
 
-DriveStraight::DriveStraight(double distance, Drivetrain* drivetrain)
+DriveStraight::DriveStraight(double distance, Drivetrain& drivetrain)
     : frc2::CommandHelper<frc2::PIDCommand, DriveStraight>(
           frc2::PIDController(4, 0, 0),
-          [drivetrain] { return drivetrain->GetDistance(); }, distance,
-          [drivetrain](double output) { drivetrain->Drive(output, output); },
-          {drivetrain}),
-      m_drivetrain(drivetrain) {
+          [&drivetrain] { return drivetrain.GetDistance(); }, distance,
+          [&drivetrain](double output) { drivetrain.Drive(output, output); },
+          {&drivetrain}),
+      m_drivetrain(&drivetrain) {
   m_controller.SetTolerance(0.01);
 }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/OpenClaw.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/OpenClaw.cpp
index e05b7bd..e5bab77 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/OpenClaw.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/OpenClaw.cpp
@@ -6,8 +6,8 @@
 
 #include "Robot.h"
 
-OpenClaw::OpenClaw(Claw* claw)
-    : frc2::CommandHelper<frc2::WaitCommand, OpenClaw>(1_s), m_claw(claw) {
+OpenClaw::OpenClaw(Claw& claw)
+    : frc2::CommandHelper<frc2::WaitCommand, OpenClaw>(1_s), m_claw(&claw) {
   SetName("OpenClaw");
   AddRequirements({m_claw});
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Pickup.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Pickup.cpp
index 7d32ef4..3349f62 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Pickup.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Pickup.cpp
@@ -10,7 +10,7 @@
 #include "commands/SetElevatorSetpoint.h"
 #include "commands/SetWristSetpoint.h"
 
-Pickup::Pickup(Claw* claw, Wrist* wrist, Elevator* elevator) {
+Pickup::Pickup(Claw& claw, Wrist& wrist, Elevator& elevator) {
   SetName("Pickup");
   AddCommands(CloseClaw(claw),
               frc2::ParallelCommandGroup(SetWristSetpoint(-45, wrist),
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Place.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Place.cpp
index ff52a8f..2fae0f2 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Place.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Place.cpp
@@ -8,7 +8,7 @@
 #include "commands/SetElevatorSetpoint.h"
 #include "commands/SetWristSetpoint.h"
 
-Place::Place(Claw* claw, Wrist* wrist, Elevator* elevator) {
+Place::Place(Claw& claw, Wrist& wrist, Elevator& elevator) {
   SetName("Place");
   // clang-format off
   AddCommands(SetElevatorSetpoint(0.25, elevator),
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/PrepareToPickup.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/PrepareToPickup.cpp
index 2a05e25..6f01c8a 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/PrepareToPickup.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/PrepareToPickup.cpp
@@ -10,7 +10,7 @@
 #include "commands/SetElevatorSetpoint.h"
 #include "commands/SetWristSetpoint.h"
 
-PrepareToPickup::PrepareToPickup(Claw* claw, Wrist* wrist, Elevator* elevator) {
+PrepareToPickup::PrepareToPickup(Claw& claw, Wrist& wrist, Elevator& elevator) {
   SetName("PrepareToPickup");
   AddCommands(OpenClaw(claw),
               frc2::ParallelCommandGroup(SetElevatorSetpoint(0, elevator),
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetDistanceToBox.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetDistanceToBox.cpp
index d594797..84bf237 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetDistanceToBox.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetDistanceToBox.cpp
@@ -8,14 +8,14 @@
 
 #include "Robot.h"
 
-SetDistanceToBox::SetDistanceToBox(double distance, Drivetrain* drivetrain)
+SetDistanceToBox::SetDistanceToBox(double distance, Drivetrain& drivetrain)
     : frc2::CommandHelper<frc2::PIDCommand, SetDistanceToBox>(
           frc2::PIDController(-2, 0, 0),
-          [drivetrain] { return drivetrain->GetDistanceToObstacle(); },
+          [&drivetrain] { return drivetrain.GetDistanceToObstacle(); },
           distance,
-          [drivetrain](double output) { drivetrain->Drive(output, output); },
-          {drivetrain}),
-      m_drivetrain(drivetrain) {
+          [&drivetrain](double output) { drivetrain.Drive(output, output); },
+          {&drivetrain}),
+      m_drivetrain(&drivetrain) {
   m_controller.SetTolerance(0.01);
 }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetElevatorSetpoint.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetElevatorSetpoint.cpp
index e539903..08343fe 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetElevatorSetpoint.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetElevatorSetpoint.cpp
@@ -8,8 +8,8 @@
 
 #include "Robot.h"
 
-SetElevatorSetpoint::SetElevatorSetpoint(double setpoint, Elevator* elevator)
-    : m_setpoint(setpoint), m_elevator(elevator) {
+SetElevatorSetpoint::SetElevatorSetpoint(double setpoint, Elevator& elevator)
+    : m_setpoint(setpoint), m_elevator(&elevator) {
   SetName("SetElevatorSetpoint");
   AddRequirements({m_elevator});
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetWristSetpoint.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetWristSetpoint.cpp
index 5063a99..9697745 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetWristSetpoint.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetWristSetpoint.cpp
@@ -6,8 +6,8 @@
 
 #include "Robot.h"
 
-SetWristSetpoint::SetWristSetpoint(double setpoint, Wrist* wrist)
-    : m_setpoint(setpoint), m_wrist(wrist) {
+SetWristSetpoint::SetWristSetpoint(double setpoint, Wrist& wrist)
+    : m_setpoint(setpoint), m_wrist(&wrist) {
   SetName("SetWristSetpoint");
   AddRequirements({m_wrist});
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/TankDrive.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/TankDrive.cpp
index a68edab..cc34e53 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/TankDrive.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/TankDrive.cpp
@@ -9,10 +9,10 @@
 #include "Robot.h"
 
 TankDrive::TankDrive(std::function<double()> left,
-                     std::function<double()> right, Drivetrain* drivetrain)
+                     std::function<double()> right, Drivetrain& drivetrain)
     : m_left(std::move(left)),
       m_right(std::move(right)),
-      m_drivetrain(drivetrain) {
+      m_drivetrain(&drivetrain) {
   SetName("TankDrive");
   AddRequirements({m_drivetrain});
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Claw.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Claw.cpp
index b1560da..fa0e94d 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Claw.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Claw.cpp
@@ -24,7 +24,7 @@
   m_motor.Set(0);
 }
 
-bool Claw::IsGripping() {
+bool Claw::IsGripping() const {
   return m_contact.Get();
 }
 
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 f3d41a2..16d6e46 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Drivetrain.cpp
@@ -55,7 +55,7 @@
   m_robotDrive.TankDrive(left, right);
 }
 
-double Drivetrain::GetHeading() {
+double Drivetrain::GetHeading() const {
   return m_gyro.GetAngle();
 }
 
@@ -65,11 +65,11 @@
   m_rightEncoder.Reset();
 }
 
-double Drivetrain::GetDistance() {
+double Drivetrain::GetDistance() const {
   return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.0;
 }
 
-double Drivetrain::GetDistanceToObstacle() {
+double Drivetrain::GetDistanceToObstacle() const {
   // Really meters in simulation since it's a rangefinder...
   return m_rangefinder.GetAverageVoltage();
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Wrist.cpp b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Wrist.cpp
index fb3ab35..339ccd0 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Wrist.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Wrist.cpp
@@ -7,10 +7,7 @@
 #include <frc/controller/PIDController.h>
 #include <frc/smartdashboard/SmartDashboard.h>
 
-Wrist::Wrist() : frc2::PIDSubsystem(frc2::PIDController(kP_real, 0, 0)) {
-#ifdef SIMULATION  // Check for simulation and update PID values
-  GetPIDController()->SetPID(kP_simulation, 0, 0, 0);
-#endif
+Wrist::Wrist() : frc2::PIDSubsystem(frc2::PIDController(kP, 0, 0)) {
   m_controller.SetTolerance(2.5);
 
   SetName("Wrist");
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Autonomous.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Autonomous.h
index 5dae1c1..a9a5bf4 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Autonomous.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Autonomous.h
@@ -18,6 +18,6 @@
 class Autonomous
     : public frc2::CommandHelper<frc2::SequentialCommandGroup, Autonomous> {
  public:
-  Autonomous(Claw* claw, Wrist* wrist, Elevator* elevator,
-             Drivetrain* drivetrain);
+  Autonomous(Claw& claw, Wrist& wrist, Elevator& elevator,
+             Drivetrain& drivetrain);
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/CloseClaw.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/CloseClaw.h
index fe8133b..0511604 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/CloseClaw.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/CloseClaw.h
@@ -14,7 +14,7 @@
  */
 class CloseClaw : public frc2::CommandHelper<frc2::CommandBase, CloseClaw> {
  public:
-  explicit CloseClaw(Claw* claw);
+  explicit CloseClaw(Claw& claw);
   void Initialize() override;
   bool IsFinished() override;
   void End(bool interrupted) override;
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/DriveStraight.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/DriveStraight.h
index abc598c..c196232 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/DriveStraight.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/DriveStraight.h
@@ -18,7 +18,7 @@
 class DriveStraight
     : public frc2::CommandHelper<frc2::PIDCommand, DriveStraight> {
  public:
-  explicit DriveStraight(double distance, Drivetrain* drivetrain);
+  explicit DriveStraight(double distance, Drivetrain& drivetrain);
   void Initialize() override;
   bool IsFinished() override;
 
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/OpenClaw.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/OpenClaw.h
index f7b3d0f..e6fe962 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/OpenClaw.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/OpenClaw.h
@@ -15,7 +15,7 @@
  */
 class OpenClaw : public frc2::CommandHelper<frc2::WaitCommand, OpenClaw> {
  public:
-  explicit OpenClaw(Claw* claw);
+  explicit OpenClaw(Claw& claw);
   void Initialize() override;
   void End(bool interrupted) override;
 
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Pickup.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Pickup.h
index 33327eb..ba0b02f 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Pickup.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Pickup.h
@@ -18,5 +18,5 @@
 class Pickup
     : public frc2::CommandHelper<frc2::SequentialCommandGroup, Pickup> {
  public:
-  Pickup(Claw* claw, Wrist* wrist, Elevator* elevator);
+  Pickup(Claw& claw, Wrist& wrist, Elevator& elevator);
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Place.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Place.h
index 353ef1c..02b043f 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Place.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Place.h
@@ -16,5 +16,5 @@
  */
 class Place : public frc2::CommandHelper<frc2::SequentialCommandGroup, Place> {
  public:
-  Place(Claw* claw, Wrist* wrist, Elevator* elevator);
+  Place(Claw& claw, Wrist& wrist, Elevator& elevator);
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/PrepareToPickup.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/PrepareToPickup.h
index 0289d4f..b219cf0 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/PrepareToPickup.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/PrepareToPickup.h
@@ -17,5 +17,5 @@
 class PrepareToPickup : public frc2::CommandHelper<frc2::SequentialCommandGroup,
                                                    PrepareToPickup> {
  public:
-  PrepareToPickup(Claw* claw, Wrist* wrist, Elevator* elevator);
+  PrepareToPickup(Claw& claw, Wrist& wrist, Elevator& elevator);
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetDistanceToBox.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetDistanceToBox.h
index 2104a5c..1d2672a 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetDistanceToBox.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetDistanceToBox.h
@@ -18,7 +18,7 @@
 class SetDistanceToBox
     : public frc2::CommandHelper<frc2::PIDCommand, SetDistanceToBox> {
  public:
-  explicit SetDistanceToBox(double distance, Drivetrain* drivetrain);
+  explicit SetDistanceToBox(double distance, Drivetrain& drivetrain);
   void Initialize() override;
   bool IsFinished() override;
 
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetElevatorSetpoint.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetElevatorSetpoint.h
index 8df402d..a106d62 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetElevatorSetpoint.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetElevatorSetpoint.h
@@ -19,7 +19,7 @@
 class SetElevatorSetpoint
     : public frc2::CommandHelper<frc2::CommandBase, SetElevatorSetpoint> {
  public:
-  explicit SetElevatorSetpoint(double setpoint, Elevator* elevator);
+  explicit SetElevatorSetpoint(double setpoint, Elevator& elevator);
   void Initialize() override;
   bool IsFinished() override;
 
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetWristSetpoint.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetWristSetpoint.h
index e362b30..2f6ca21 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetWristSetpoint.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetWristSetpoint.h
@@ -17,7 +17,7 @@
 class SetWristSetpoint
     : public frc2::CommandHelper<frc2::CommandBase, SetWristSetpoint> {
  public:
-  explicit SetWristSetpoint(double setpoint, Wrist* wrist);
+  explicit SetWristSetpoint(double setpoint, Wrist& wrist);
   void Initialize() override;
   bool IsFinished() override;
 
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/TankDrive.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/TankDrive.h
index c49fdf3..5a81c11 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/TankDrive.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/TankDrive.h
@@ -15,7 +15,7 @@
 class TankDrive : public frc2::CommandHelper<frc2::CommandBase, TankDrive> {
  public:
   TankDrive(std::function<double()> left, std::function<double()> right,
-            Drivetrain* drivetrain);
+            Drivetrain& drivetrain);
   void Execute() override;
   bool IsFinished() override;
   void End(bool interrupted) override;
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h
index 3b65382..c6f17d8 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h
@@ -36,7 +36,7 @@
    * Return true when the robot is grabbing an object hard enough
    * to trigger the limit switch.
    */
-  bool IsGripping();
+  bool IsGripping() const;
 
   /**
    * The log method puts interesting information to the SmartDashboard.
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 108a9c0..9e739c4 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Drivetrain.h
@@ -40,7 +40,7 @@
   /**
    * @return The robots heading in degrees.
    */
-  double GetHeading();
+  double GetHeading() const;
 
   /**
    * Reset the robots sensors to the zero states.
@@ -50,12 +50,12 @@
   /**
    * @return The distance driven (average of left and right encoders).
    */
-  double GetDistance();
+  double GetDistance() const;
 
   /**
    * @return The distance to the obstacle detected by the rangefinder.
    */
-  double GetDistanceToObstacle();
+  double GetDistanceToObstacle() const;
 
   /**
    * Log the data periodically. This method is automatically called
diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Wrist.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Wrist.h
index e873c2c..7df08b9 100644
--- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Wrist.h
+++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Wrist.h
@@ -51,6 +51,5 @@
   frc::AnalogPotentiometer m_pot{3};  // Defaults to degrees
 #endif
 
-  static constexpr double kP_real = 1;
-  static constexpr double kP_simulation = 0.05;
+  static constexpr double kP = 1;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp
index 6b7d2b6..003a08a 100644
--- a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp
@@ -11,7 +11,11 @@
 class Robot : public frc::TimedRobot {
  public:
   Robot() {
+    m_right.SetInverted(true);
     m_robotDrive.SetExpiration(100_ms);
+    // 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_timer.Start();
   }
 
@@ -35,7 +39,7 @@
 
   void TeleopPeriodic() override {
     // Drive with arcade style (use right stick)
-    m_robotDrive.ArcadeDrive(m_stick.GetY(), m_stick.GetX());
+    m_robotDrive.ArcadeDrive(-m_stick.GetY(), m_stick.GetX());
   }
 
   void TestInit() override {}
diff --git a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp
index 1dda356..0e1410e 100644
--- a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp
@@ -17,7 +17,13 @@
  */
 class Robot : public frc::TimedRobot {
  public:
-  void RobotInit() override { m_gyro.SetSensitivity(kVoltsPerDegreePerSecond); }
+  void RobotInit() override {
+    m_gyro.SetSensitivity(kVoltsPerDegreePerSecond);
+    // 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);
+  }
 
   /**
    * The motor speed is set from the joystick while the DifferentialDrive
@@ -28,7 +34,7 @@
     double turningValue = (kAngleSetpoint - m_gyro.GetAngle()) * kP;
     // Invert the direction of the turn if we are going backwards
     turningValue = std::copysign(turningValue, m_joystick.GetY());
-    m_robotDrive.ArcadeDrive(m_joystick.GetY(), turningValue);
+    m_robotDrive.ArcadeDrive(-m_joystick.GetY(), turningValue);
   }
 
  private:
diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/Robot.cpp
index 8cd7b02..c7eab48 100644
--- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/Robot.cpp
@@ -10,7 +10,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp
index eb95395..6f5911e 100644
--- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/RobotContainer.cpp
@@ -19,7 +19,7 @@
   // Set up default drive command
   m_drive.SetDefaultCommand(frc2::RunCommand(
       [this] {
-        m_drive.ArcadeDrive(m_driverController.GetLeftY(),
+        m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
                             m_driverController.GetRightX());
       },
       {&m_drive}));
diff --git a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp
index 5885873..a4e0457 100644
--- a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp
@@ -10,16 +10,16 @@
 
 /**
  * This is a sample program that uses mecanum drive with a gyro sensor to
- * maintain rotation vectorsin relation to the starting orientation of the robot
- * (field-oriented controls).
+ * maintain rotation vectors in relation to the starting orientation of the
+ * robot (field-oriented controls).
  */
 class Robot : public frc::TimedRobot {
  public:
   void RobotInit() override {
-    // Invert the left side motors. You may need to change or remove this to
+    // Invert the right side motors. You may need to change or remove this to
     // match your robot.
-    m_frontLeft.SetInverted(true);
-    m_rearLeft.SetInverted(true);
+    m_frontRight.SetInverted(true);
+    m_rearRight.SetInverted(true);
 
     m_gyro.SetSensitivity(kVoltsPerDegreePerSecond);
   }
@@ -28,7 +28,7 @@
    * Mecanum drive is used with the gyro angle as an input.
    */
   void TeleopPeriodic() override {
-    m_robotDrive.DriveCartesian(m_joystick.GetX(), m_joystick.GetY(),
+    m_robotDrive.DriveCartesian(-m_joystick.GetY(), m_joystick.GetX(),
                                 m_joystick.GetZ(), m_gyro.GetAngle());
   }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp
index 8cd7b02..c7eab48 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp
@@ -10,7 +10,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp
index 31a78b5..8fae7d2 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp
@@ -23,7 +23,7 @@
   // Set up default drive command
   m_drive.SetDefaultCommand(frc2::RunCommand(
       [this] {
-        m_drive.ArcadeDrive(m_driverController.GetLeftY(),
+        m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
                             m_driverController.GetRightX());
       },
       {&m_drive}));
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp
index 8cd7b02..c7eab48 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp
@@ -10,7 +10,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp
index b46efd4..6f8c5a6 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp
@@ -27,7 +27,7 @@
 
   // Set up default drive command
   m_drive.SetDefaultCommand(DefaultDrive(
-      &m_drive, [this] { return m_driverController.GetLeftY(); },
+      &m_drive, [this] { return -m_driverController.GetLeftY(); },
       [this] { return m_driverController.GetRightX(); }));
 }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/I2CCommunication/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/I2CCommunication/cpp/Robot.cpp
new file mode 100644
index 0000000..fad7581
--- /dev/null
+++ b/wpilibcExamples/src/main/cpp/examples/I2CCommunication/cpp/Robot.cpp
@@ -0,0 +1,49 @@
+// Copyright (c) FIRST and other WPILib contributors.
+// Open Source Software; you can modify and/or share it under the terms of
+// the WPILib BSD license file in the root directory of this project.
+
+#include <fmt/format.h>
+
+#include <frc/DriverStation.h>
+#include <frc/I2C.h>
+#include <frc/TimedRobot.h>
+#include <frc/Timer.h>
+
+/**
+ * This is a sample program demonstrating how to communicate to a light
+ * controller from the robot code using the roboRIO's I2C port.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  void RobotPeriodic() override {
+    // Creates a string to hold current robot state information, including
+    // alliance, enabled state, operation mode, and match time. The message
+    // is sent in format "AEM###" where A is the alliance color, (R)ed or
+    // (B)lue, E is the enabled state, (E)nabled or (D)isabled, M is the
+    // operation mode, (A)utonomous or (T)eleop, and ### is the zero-padded
+    // time remaining in the match.
+    //
+    // For example, "RET043" would indicate that the robot is on the red
+    // alliance, enabled in teleop mode, with 43 seconds left in the match.
+    auto string = fmt::format(
+        "{}{}{}{:03}",
+        frc::DriverStation::GetAlliance() == frc::DriverStation::Alliance::kRed
+            ? "R"
+            : "B",
+        frc::DriverStation::IsEnabled() ? "E" : "D",
+        frc::DriverStation::IsAutonomous() ? "A" : "T",
+        static_cast<int>(frc::Timer::GetMatchTime().value()));
+
+    arduino.WriteBulk(reinterpret_cast<uint8_t*>(string.data()), string.size());
+  }
+
+ private:
+  static constexpr int deviceAddress = 4;
+  frc::I2C arduino{frc::I2C::Port::kOnboard, deviceAddress};
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() {
+  return frc::StartRobot<Robot>();
+}
+#endif
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Drivetrain.cpp
index c33450d..4d3aac2 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Drivetrain.cpp
@@ -47,7 +47,7 @@
       fieldRelative ? frc::ChassisSpeeds::FromFieldRelativeSpeeds(
                           xSpeed, ySpeed, rot, m_gyro.GetRotation2d())
                     : frc::ChassisSpeeds{xSpeed, ySpeed, rot});
-  wheelSpeeds.Normalize(kMaxSpeed);
+  wheelSpeeds.Desaturate(kMaxSpeed);
   SetSpeeds(wheelSpeeds);
 }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h
index 0aa3086..9ec5fc5 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.h
@@ -20,7 +20,14 @@
  */
 class Drivetrain {
  public:
-  Drivetrain() { m_gyro.Reset(); }
+  Drivetrain() {
+    m_gyro.Reset();
+    // 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_frontRightMotor.SetInverted(true);
+    m_backRightMotor.SetInverted(true);
+  }
 
   frc::MecanumDriveWheelSpeeds GetCurrentState() const;
   void SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds);
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Robot.cpp
index 8cd7b02..c7eab48 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/Robot.cpp
@@ -10,7 +10,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
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 4cc4e47..9e06068 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/cpp/subsystems/DriveSubsystem.cpp
@@ -34,6 +34,11 @@
   m_rearLeftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
   m_frontRightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
   m_rearRightEncoder.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_frontRight.SetInverted(true);
+  m_rearRight.SetInverted(true);
 }
 
 void DriveSubsystem::Periodic() {
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h
index 592e948..8d59a2c 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/Constants.h
@@ -56,9 +56,8 @@
 
 // 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 RobotPy Characterization
-// Toolsuite provides a convenient tool for obtaining these values for your
-// robot.
+// 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;
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp
index 822e9ee..f8d95ac 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp
@@ -14,17 +14,18 @@
 class Robot : public frc::TimedRobot {
  public:
   void RobotInit() override {
-    // Invert the left side motors. You may need to change or remove this to
+    // Invert the right side motors. You may need to change or remove this to
     // match your robot.
-    m_frontLeft.SetInverted(true);
-    m_rearLeft.SetInverted(true);
+    m_frontRight.SetInverted(true);
+    m_rearRight.SetInverted(true);
   }
 
   void TeleopPeriodic() override {
     /* Use the joystick X axis for lateral movement, Y axis for forward
      * movement, and Z axis for rotation.
      */
-    m_robotDrive.DriveCartesian(m_stick.GetX(), m_stick.GetY(), m_stick.GetZ());
+    m_robotDrive.DriveCartesian(-m_stick.GetY(), m_stick.GetX(),
+                                m_stick.GetZ());
   }
 
  private:
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp
index 149f12e..daa4b42 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp
@@ -44,7 +44,7 @@
       fieldRelative ? frc::ChassisSpeeds::FromFieldRelativeSpeeds(
                           xSpeed, ySpeed, rot, m_gyro.GetRotation2d())
                     : frc::ChassisSpeeds{xSpeed, ySpeed, rot});
-  wheelSpeeds.Normalize(kMaxSpeed);
+  wheelSpeeds.Desaturate(kMaxSpeed);
   SetSpeeds(wheelSpeeds);
 }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.h
index d084fa5..3eea4a2 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.h
@@ -21,7 +21,14 @@
  */
 class Drivetrain {
  public:
-  Drivetrain() { m_gyro.Reset(); }
+  Drivetrain() {
+    m_gyro.Reset();
+    // 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_frontRightMotor.SetInverted(true);
+    m_backRightMotor.SetInverted(true);
+  }
 
   frc::MecanumDriveWheelSpeeds GetCurrentState() const;
   void SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds);
diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/Robot.cpp
index 8cd7b02..c7eab48 100644
--- a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/Robot.cpp
@@ -10,7 +10,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
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 78355a2..a5b853e 100644
--- a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp
@@ -42,7 +42,7 @@
 
 void DriveSubsystem::TankDriveVolts(units::volt_t left, units::volt_t right) {
   m_leftMotors.SetVoltage(left);
-  m_rightMotors.SetVoltage(-right);
+  m_rightMotors.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 cdd3a43..174a028 100644
--- a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h
@@ -5,6 +5,7 @@
 #include <frc/kinematics/DifferentialDriveKinematics.h>
 #include <frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h>
 #include <units/acceleration.h>
+#include <units/angle.h>
 #include <units/length.h>
 #include <units/time.h>
 #include <units/velocity.h>
@@ -62,8 +63,8 @@
 
 // Reasonable baseline values for a RAMSETE follower in units of meters and
 // seconds
-constexpr double kRamseteB = 2;
-constexpr double kRamseteZeta = 0.7;
+constexpr auto kRamseteB = 2.0 * 1_rad * 1_rad / (1_m * 1_m);
+constexpr auto kRamseteZeta = 0.7 / 1_rad;
 }  // namespace AutoConstants
 
 namespace OIConstants {
diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp
index fa9438d..e39a8fd 100644
--- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp
@@ -9,7 +9,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/OnBoardIO.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/OnBoardIO.cpp
index b178ec0..1b76c74 100644
--- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/OnBoardIO.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/OnBoardIO.cpp
@@ -17,6 +17,7 @@
   }
   if (dio2 == ChannelMode::INPUT) {
     m_buttonC = std::make_unique<frc::DigitalInput>(2);
+  } else {
     m_redLed = std::make_unique<frc::DigitalOutput>(2);
   }
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/SchedulerEventLogging/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SchedulerEventLogging/cpp/Robot.cpp
index 8cd7b02..c7eab48 100644
--- a/wpilibcExamples/src/main/cpp/examples/SchedulerEventLogging/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SchedulerEventLogging/cpp/Robot.cpp
@@ -10,7 +10,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
diff --git a/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp
index 8cd7b02..c7eab48 100644
--- a/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp
@@ -10,7 +10,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
diff --git a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp
index 05d99f3..098b997 100644
--- a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp
@@ -41,9 +41,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_leftLeader.Get()} *
+  m_drivetrainSimulator.SetInputs(units::volt_t{m_leftGroup.Get()} *
                                       frc::RobotController::GetInputVoltage(),
-                                  units::volt_t{-m_rightLeader.Get()} *
+                                  units::volt_t{m_rightGroup.Get()} *
                                       frc::RobotController::GetInputVoltage());
   m_drivetrainSimulator.Update(20_ms);
 
diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/Robot.cpp
index 0920db7..318dc61 100644
--- a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/Robot.cpp
@@ -16,7 +16,7 @@
 }
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/RobotContainer.cpp
index 554de50..a4245d6 100644
--- a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/RobotContainer.cpp
@@ -28,7 +28,7 @@
   // Set up default drive command
   m_drive.SetDefaultCommand(frc2::RunCommand(
       [this] {
-        m_drive.ArcadeDrive(m_driverController.GetLeftY(),
+        m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
                             m_driverController.GetRightX());
       },
       {&m_drive}));
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 a94b860..0971549 100644
--- a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp
@@ -42,7 +42,7 @@
   // 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()} *
+                                  units::volt_t{m_rightMotors.Get()} *
                                       frc::RobotController::GetInputVoltage());
   m_drivetrainSimulator.Update(20_ms);
 
@@ -64,7 +64,7 @@
 
 void DriveSubsystem::TankDriveVolts(units::volt_t left, units::volt_t right) {
   m_leftMotors.SetVoltage(left);
-  m_rightMotors.SetVoltage(-right);
+  m_rightMotors.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 307d408..b12eef1 100644
--- a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h
@@ -74,8 +74,8 @@
 
 // Reasonable baseline values for a RAMSETE follower in units of meters and
 // seconds
-constexpr double kRamseteB = 2;
-constexpr double kRamseteZeta = 0.7;
+constexpr auto kRamseteB = 2 * 1_rad * 1_rad / (1_m * 1_m);
+constexpr auto kRamseteZeta = 0.7 / 1_rad;
 }  // namespace AutoConstants
 
 namespace OIConstants {
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Drivetrain.cpp
index 7044fd7..709f403 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Drivetrain.cpp
@@ -12,7 +12,7 @@
                           xSpeed, ySpeed, rot, m_gyro.GetRotation2d())
                     : frc::ChassisSpeeds{xSpeed, ySpeed, rot});
 
-  m_kinematics.NormalizeWheelSpeeds(&states, kMaxSpeed);
+  m_kinematics.DesaturateWheelSpeeds(&states, kMaxSpeed);
 
   auto [fl, fr, bl, br] = states;
 
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.h
index 6ff5b48..2b3cc0e 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.h
@@ -36,7 +36,7 @@
   frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m};
 
   SwerveModule m_frontLeft{1, 2, 0, 1, 2, 3};
-  SwerveModule m_frontRight{2, 3, 4, 5, 6, 7};
+  SwerveModule m_frontRight{3, 4, 4, 5, 6, 7};
   SwerveModule m_backLeft{5, 6, 8, 9, 10, 11};
   SwerveModule m_backRight{7, 8, 12, 13, 14, 15};
 
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/Robot.cpp
index 8cd7b02..c7eab48 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/Robot.cpp
@@ -10,7 +10,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp
index 4ee98ae..a35314e 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/RobotContainer.cpp
@@ -30,12 +30,14 @@
   ConfigureButtonBindings();
 
   // Set up default drive command
+  // The left stick controls translation of the robot.
+  // Turning is controlled by the X axis of the right stick.
   m_drive.SetDefaultCommand(frc2::RunCommand(
       [this] {
         m_drive.Drive(
             units::meters_per_second_t(m_driverController.GetLeftY()),
-            units::meters_per_second_t(m_driverController.GetRightY()),
-            units::radians_per_second_t(m_driverController.GetLeftX()), false);
+            units::meters_per_second_t(m_driverController.GetLeftX()),
+            units::radians_per_second_t(m_driverController.GetRightX()), false);
       },
       {&m_drive}));
 }
@@ -84,7 +86,7 @@
 
   // no auto
   return new frc2::SequentialCommandGroup(
-      std::move(swerveControllerCommand), std::move(swerveControllerCommand),
+      std::move(swerveControllerCommand),
       frc2::InstantCommand(
           [this]() {
             m_drive.Drive(units::meters_per_second_t(0),
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/DriveSubsystem.cpp
index 7ef4af3..fd15100 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/cpp/subsystems/DriveSubsystem.cpp
@@ -54,7 +54,7 @@
                           xSpeed, ySpeed, rot, m_gyro.GetRotation2d())
                     : frc::ChassisSpeeds{xSpeed, ySpeed, rot});
 
-  kDriveKinematics.NormalizeWheelSpeeds(&states, AutoConstants::kMaxSpeed);
+  kDriveKinematics.DesaturateWheelSpeeds(&states, AutoConstants::kMaxSpeed);
 
   auto [fl, fr, bl, br] = states;
 
@@ -66,11 +66,11 @@
 
 void DriveSubsystem::SetModuleStates(
     wpi::array<frc::SwerveModuleState, 4> desiredStates) {
-  kDriveKinematics.NormalizeWheelSpeeds(&desiredStates,
-                                        AutoConstants::kMaxSpeed);
+  kDriveKinematics.DesaturateWheelSpeeds(&desiredStates,
+                                         AutoConstants::kMaxSpeed);
   m_frontLeft.SetDesiredState(desiredStates[0]);
-  m_rearLeft.SetDesiredState(desiredStates[1]);
-  m_frontRight.SetDesiredState(desiredStates[2]);
+  m_frontRight.SetDesiredState(desiredStates[1]);
+  m_rearLeft.SetDesiredState(desiredStates[2]);
   m_rearRight.SetDesiredState(desiredStates[3]);
 }
 
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h
index 3a3b75a..e6fa136 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/Constants.h
@@ -58,9 +58,8 @@
 
 // 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 RobotPy Characterization
-// Toolsuite provides a convenient tool for obtaining these values for your
-// robot.
+// 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;
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp
index f132f76..33a3233 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp
@@ -16,7 +16,7 @@
                           xSpeed, ySpeed, rot, m_gyro.GetRotation2d())
                     : frc::ChassisSpeeds{xSpeed, ySpeed, rot});
 
-  m_kinematics.NormalizeWheelSpeeds(&states, kMaxSpeed);
+  m_kinematics.DesaturateWheelSpeeds(&states, kMaxSpeed);
 
   auto [fl, fr, bl, br] = states;
 
diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.h
index 81f8bb7..f525729 100644
--- a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.h
+++ b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.h
@@ -36,7 +36,7 @@
   frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m};
 
   SwerveModule m_frontLeft{1, 2, 0, 1, 2, 3};
-  SwerveModule m_frontRight{2, 3, 4, 5, 6, 7};
+  SwerveModule m_frontRight{3, 4, 4, 5, 6, 7};
   SwerveModule m_backLeft{5, 6, 8, 9, 10, 11};
   SwerveModule m_backRight{7, 8, 12, 13, 14, 15};
 
diff --git a/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp
index 466fdcd..b8cff32 100644
--- a/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp
@@ -27,8 +27,8 @@
 
   void TeleopPeriodic() override {
     // Drive with tank style
-    m_robotDrive.TankDrive(m_driverController.GetLeftY(),
-                           m_driverController.GetRightY());
+    m_robotDrive.TankDrive(-m_driverController.GetLeftY(),
+                           -m_driverController.GetRightY());
   }
 };
 
diff --git a/wpilibcExamples/src/main/cpp/examples/examples.json b/wpilibcExamples/src/main/cpp/examples/examples.json
index b639188..9eb5b6b 100644
--- a/wpilibcExamples/src/main/cpp/examples/examples.json
+++ b/wpilibcExamples/src/main/cpp/examples/examples.json
@@ -261,6 +261,27 @@
     "commandversion": 2
   },
   {
+    "name": "I2C Communication",
+    "description": "An example program that communicates with external devices (such as an Arduino) using the roboRIO's I2C port",
+    "tags": [
+      "I2C"
+    ],
+    "foldername": "I2CCommunication",
+    "gradlebase": "cpp",
+    "commandversion": 2
+  },
+  {
+    "name": "Digital Communication Sample",
+    "description": "An example program that communicates with external devices (such as an Arduino) using the roboRIO's DIO",
+    "tags": [
+      "Digital"
+    ],
+    "foldername": "DigitalCommunication",
+    "gradlebase": "cpp",
+    "commandversion": 2
+  },
+
+  {
     "name": "Axis Camera Sample",
     "description": "An example program that acquires images from an Axis network camera and adds some annotation to the image as you might do for showing operators the result of some image recognition, and sends it to the dashboard for display. This demonstrates the use of the AxisCamera class.",
     "tags": [
@@ -692,7 +713,8 @@
       "Sensors",
       "Simulation",
       "Physics",
-      "Mechanism2d"
+      "Mechanism2d",
+      "Preferences"
     ],
     "foldername": "ArmSimulation",
     "gradlebase": "cpp",
diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp
index 8cd7b02..426b989 100644
--- a/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp
@@ -10,7 +10,7 @@
 void Robot::RobotInit() {}
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want to run during disabled,
  * autonomous, teleoperated and test.
  *
@@ -65,6 +65,16 @@
  */
 void Robot::TestPeriodic() {}
 
+/**
+ * This function is called once when the robot is first started up.
+ */
+void Robot::SimulationInit() {}
+
+/**
+ * This function is called periodically whilst in simulation.
+ */
+void Robot::SimulationPeriodic() {}
+
 #ifndef RUNNING_FRC_TESTS
 int main() {
   return frc::StartRobot<Robot>();
diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h b/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h
index a82f2ac..25e3229 100644
--- a/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h
+++ b/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h
@@ -20,6 +20,8 @@
   void TeleopInit() override;
   void TeleopPeriodic() override;
   void TestPeriodic() override;
+  void SimulationInit() override;
+  void SimulationPeriodic() override;
 
  private:
   // Have it null by default so that if testing teleop it
diff --git a/wpilibcExamples/src/main/cpp/templates/templates.json b/wpilibcExamples/src/main/cpp/templates/templates.json
index 59d4084..83260a0 100644
--- a/wpilibcExamples/src/main/cpp/templates/templates.json
+++ b/wpilibcExamples/src/main/cpp/templates/templates.json
@@ -1,5 +1,15 @@
 [
   {
+    "name": "Command Robot",
+    "description": "Command style",
+    "tags": [
+      "Command"
+    ],
+    "foldername": "commandbased",
+    "gradlebase": "cpp",
+    "commandversion": 2
+  },
+  {
     "name": "Timed Robot",
     "description": "Timed style",
     "tags": [
@@ -30,13 +40,13 @@
     "commandversion": 2
   },
   {
-    "name": "Command Robot",
-    "description": "Command style",
+    "name": "Romi - Command Robot",
+    "description": "Romi - Command style",
     "tags": [
-      "Command"
+      "Command", "Romi"
     ],
     "foldername": "commandbased",
-    "gradlebase": "cpp",
+    "gradlebase": "cppromi",
     "commandversion": 2
   },
   {
@@ -48,15 +58,5 @@
     "foldername": "timed",
     "gradlebase": "cppromi",
     "commandversion": 2
-  },
-  {
-    "name": "Romi - Command Robot",
-    "description": "Romi - Command style",
-    "tags": [
-      "Command", "Romi"
-    ],
-    "foldername": "commandbased",
-    "gradlebase": "cppromi",
-    "commandversion": 2
   }
 ]
diff --git a/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp
index 577de89..2fcc80b 100644
--- a/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp
@@ -15,7 +15,7 @@
 }
 
 /**
- * This function is called every robot packet, no matter the mode. Use
+ * This function is called every 20 ms, no matter the mode. Use
  * this for items like diagnostics that you want ran during disabled,
  * autonomous, teleoperated and test.
  *
@@ -68,6 +68,10 @@
 
 void Robot::TestPeriodic() {}
 
+void Robot::SimulationInit() {}
+
+void Robot::SimulationPeriodic() {}
+
 #ifndef RUNNING_FRC_TESTS
 int main() {
   return frc::StartRobot<Robot>();
diff --git a/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.h b/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.h
index b887605..5677a88 100644
--- a/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.h
+++ b/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.h
@@ -21,6 +21,8 @@
   void DisabledPeriodic() override;
   void TestInit() override;
   void TestPeriodic() override;
+  void SimulationInit() override;
+  void SimulationPeriodic() override;
 
  private:
   frc::SendableChooser<std::string> m_chooser;
diff --git a/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp
index 92f5df1..d5b57c2 100644
--- a/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp
@@ -19,6 +19,9 @@
 void Robot::TestInit() {}
 void Robot::TestPeriodic() {}
 
+void Robot::SimulationInit() {}
+void Robot::SimulationPeriodic() {}
+
 #ifndef RUNNING_FRC_TESTS
 int main() {
   return frc::StartRobot<Robot>();
diff --git a/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.h b/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.h
index 99f84f7..062a198 100644
--- a/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.h
+++ b/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.h
@@ -22,4 +22,7 @@
 
   void TestInit() override;
   void TestPeriodic() override;
+
+  void SimulationInit() override;
+  void SimulationPeriodic() override;
 };