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/wpilibjExamples/build.gradle b/wpilibjExamples/build.gradle
index 518b1e8..7d74e80 100644
--- a/wpilibjExamples/build.gradle
+++ b/wpilibjExamples/build.gradle
@@ -37,13 +37,13 @@
     implementation project(':wpilibOldCommands')
     implementation project(':wpilibNewCommands')
 
-    testImplementation 'org.junit.jupiter:junit-jupiter-api:5.4.2'
-    testImplementation 'org.junit.jupiter:junit-jupiter-params:5.4.2'
-    testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.4.2'
+    testImplementation 'org.junit.jupiter:junit-jupiter-api:5.8.2'
+    testImplementation 'org.junit.jupiter:junit-jupiter-params:5.8.2'
+    testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.8.2'
 }
 
 jacoco {
-    toolVersion = "0.8.4"
+    toolVersion = "0.8.7"
 }
 
 jacocoTestReport {
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java
index e35243d..5eef7e8 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrive/Robot.java
@@ -20,10 +20,18 @@
   private final Joystick m_stick = new Joystick(0);
 
   @Override
+  public void robotInit() {
+    // 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);
+  }
+
+  @Override
   public void teleopPeriodic() {
     // Drive with arcade drive.
     // That means that the Y axis drives forward
     // and backward, and the X turns left and right.
-    m_robotDrive.arcadeDrive(m_stick.getY(), m_stick.getX());
+    m_robotDrive.arcadeDrive(-m_stick.getY(), m_stick.getX());
   }
 }
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java
index 0acc8dc..656165a 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/arcadedrivexboxcontroller/Robot.java
@@ -20,10 +20,18 @@
   private final XboxController m_driverController = new XboxController(0);
 
   @Override
+  public void robotInit() {
+    // 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);
+  }
+
+  @Override
   public void teleopPeriodic() {
     // Drive with split arcade drive.
     // 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_driverController.getRightX());
+    m_robotDrive.arcadeDrive(-m_driverController.getLeftY(), m_driverController.getRightX());
   }
 }
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/Constants.java
index c7f23de..fe72d3d 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/Constants.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/Constants.java
@@ -38,7 +38,7 @@
 
     // These are fake gains; in actuality these must be determined individually for each robot
     public static final double kSVolts = 1;
-    public static final double kCosVolts = 1;
+    public static final double kGVolts = 1;
     public static final double kVVoltSecondPerRad = 0.5;
     public static final double kAVoltSecondSquaredPerRad = 0.1;
 
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/Robot.java
index 3f91253..c2dc4fc 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java
index b0d019e..4717d51 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java
@@ -42,7 +42,7 @@
         new RunCommand(
             () ->
                 m_robotDrive.arcadeDrive(
-                    m_driverController.getLeftY(), m_driverController.getRightX()),
+                    -m_driverController.getLeftY(), m_driverController.getRightX()),
             m_robotDrive));
   }
 
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/ArmSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/ArmSubsystem.java
index 298b2d5..43beedc 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/ArmSubsystem.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/ArmSubsystem.java
@@ -19,7 +19,7 @@
       new Encoder(ArmConstants.kEncoderPorts[0], ArmConstants.kEncoderPorts[1]);
   private final ArmFeedforward m_feedforward =
       new ArmFeedforward(
-          ArmConstants.kSVolts, ArmConstants.kCosVolts,
+          ArmConstants.kSVolts, ArmConstants.kGVolts,
           ArmConstants.kVVoltSecondPerRad, ArmConstants.kAVoltSecondSquaredPerRad);
 
   /** Create a new ArmSubsystem. */
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java
index 9338f30..4ecaa77 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java
@@ -46,6 +46,11 @@
     // Sets the distance per pulse for the encoders
     m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
     m_rightEncoder.setDistancePerPulse(DriveConstants.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);
   }
 
   /**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/Constants.java
index 4fd17f1..fb003aa 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/Constants.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/Constants.java
@@ -38,7 +38,7 @@
 
     // These are fake gains; in actuality these must be determined individually for each robot
     public static final double kSVolts = 1;
-    public static final double kCosVolts = 1;
+    public static final double kGVolts = 1;
     public static final double kVVoltSecondPerRad = 0.5;
     public static final double kAVoltSecondSquaredPerRad = 0.1;
 
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/Robot.java
index e0c0c7b..160146c 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java
index b0c3f76..7ea7999 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java
@@ -42,7 +42,7 @@
         new RunCommand(
             () ->
                 m_robotDrive.arcadeDrive(
-                    m_driverController.getLeftY(), m_driverController.getRightX()),
+                    -m_driverController.getLeftY(), m_driverController.getRightX()),
             m_robotDrive));
   }
 
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/ArmSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/ArmSubsystem.java
index 152700e..9e70402 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/ArmSubsystem.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/ArmSubsystem.java
@@ -16,7 +16,7 @@
       new ExampleSmartMotorController(ArmConstants.kMotorPort);
   private final ArmFeedforward m_feedforward =
       new ArmFeedforward(
-          ArmConstants.kSVolts, ArmConstants.kCosVolts,
+          ArmConstants.kSVolts, ArmConstants.kGVolts,
           ArmConstants.kVVoltSecondPerRad, ArmConstants.kAVoltSecondSquaredPerRad);
 
   /** Create a new ArmSubsystem. */
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java
index 8017719..939bcc3 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java
@@ -46,6 +46,11 @@
     // Sets the distance per pulse for the encoders
     m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
     m_rightEncoder.setDistancePerPulse(DriveConstants.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);
   }
 
   /**
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/Robot.java
index a7e4d7d..c84d922 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/Robot.java
@@ -10,6 +10,7 @@
 import edu.wpi.first.math.util.Units;
 import edu.wpi.first.wpilibj.Encoder;
 import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.Preferences;
 import edu.wpi.first.wpilibj.RobotController;
 import edu.wpi.first.wpilibj.TimedRobot;
 import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
@@ -31,8 +32,13 @@
   private static final int kEncoderBChannel = 1;
   private static final int kJoystickPort = 0;
 
+  public static final String kArmPositionKey = "ArmPosition";
+  public static final String kArmPKey = "ArmP";
+
   // The P gain for the PID controller that drives this arm.
-  private static final double kArmKp = 50.0;
+  private static double kArmKp = 50.0;
+
+  private static double armPositionDeg = 75.0;
 
   // distance per pulse = (angle per revolution) / (pulses per revolution)
   //  = (2 * PI rads) / (4096 pulses)
@@ -88,6 +94,14 @@
     // Put Mechanism 2d to SmartDashboard
     SmartDashboard.putData("Arm Sim", m_mech2d);
     m_armTower.setColor(new Color8Bit(Color.kBlue));
+
+    // Set the Arm position setpoint and P constant to Preferences if the keys don't already exist
+    if (!Preferences.containsKey(kArmPositionKey)) {
+      Preferences.setDouble(kArmPositionKey, armPositionDeg);
+    }
+    if (!Preferences.containsKey(kArmPKey)) {
+      Preferences.setDouble(kArmPKey, kArmKp);
+    }
   }
 
   @Override
@@ -110,10 +124,21 @@
   }
 
   @Override
+  public void teleopInit() {
+    // Read Preferences for Arm setpoint and kP on entering Teleop
+    armPositionDeg = Preferences.getDouble(kArmPositionKey, armPositionDeg);
+    if (kArmKp != Preferences.getDouble(kArmPKey, kArmKp)) {
+      kArmKp = Preferences.getDouble(kArmPKey, kArmKp);
+      m_controller.setP(kArmKp);
+    }
+  }
+
+  @Override
   public void teleopPeriodic() {
     if (m_joystick.getTrigger()) {
       // Here, we run PID control like normal, with a constant setpoint of 75 degrees.
-      var pidOutput = m_controller.calculate(m_encoder.getDistance(), Units.degreesToRadians(75));
+      var pidOutput =
+          m_controller.calculate(m_encoder.getDistance(), Units.degreesToRadians(armPositionDeg));
       m_motor.setVoltage(pidOutput);
     } else {
       // Otherwise, we disable the motor.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/digitalcommunication/Main.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/digitalcommunication/Main.java
new file mode 100644
index 0000000..8338aca
--- /dev/null
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/digitalcommunication/Main.java
@@ -0,0 +1,25 @@
+// 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.
+
+package edu.wpi.first.wpilibj.examples.digitalcommunication;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all. Unless you know what
+ * you are doing, do not modify this file except to change the parameter class to the startRobot
+ * call.
+ */
+public final class Main {
+  private Main() {}
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/digitalcommunication/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/digitalcommunication/Robot.java
new file mode 100644
index 0000000..85ff8d6
--- /dev/null
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/digitalcommunication/Robot.java
@@ -0,0 +1,42 @@
+// 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.
+
+package edu.wpi.first.wpilibj.examples.digitalcommunication;
+
+import edu.wpi.first.wpilibj.DigitalOutput;
+import edu.wpi.first.wpilibj.DriverStation;
+import edu.wpi.first.wpilibj.TimedRobot;
+
+/**
+ * This is a sample program demonstrating how to communicate to a light controller from the robot
+ * code using the roboRIO's DIO ports.
+ */
+public class Robot extends TimedRobot {
+  // define ports for digitalcommunication with light controller
+  private static final int kAlliancePort = 0;
+  private static final int kEnabledPort = 1;
+  private static final int kAutonomousPort = 2;
+  private static final int kAlertPort = 3;
+
+  private final DigitalOutput m_allianceOutput = new DigitalOutput(kAlliancePort);
+  private final DigitalOutput m_enabledOutput = new DigitalOutput(kEnabledPort);
+  private final DigitalOutput m_autonomousOutput = new DigitalOutput(kAutonomousPort);
+  private final DigitalOutput m_alertOutput = new DigitalOutput(kAlertPort);
+
+  @Override
+  public void robotPeriodic() {
+    // pull alliance port high if on red alliance, pull low if on blue alliance
+    m_allianceOutput.set(DriverStation.getAlliance() == DriverStation.Alliance.Red);
+
+    // pull enabled port high if enabled, low if disabled
+    m_enabledOutput.set(DriverStation.isEnabled());
+
+    // pull auto port high if in autonomous, low if in teleop (or disabled)
+    m_autonomousOutput.set(DriverStation.isAutonomous());
+
+    // pull alert port high if match time remaining is between 30 and 25 seconds
+    var matchTime = DriverStation.getMatchTime();
+    m_alertOutput.set(matchTime <= 30 && matchTime >= 25);
+  }
+}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Constants.java
index 64ba267..0c7aeeb 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Constants.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Constants.java
@@ -22,8 +22,7 @@
     // 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.
+    // The SysId tool provides a convenient method for obtaining these values for your robot.
     public static final double ksVolts = 1;
     public static final double kvVoltSecondsPerMeter = 0.8;
     public static final double kaVoltSecondsSquaredPerMeter = 0.15;
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Robot.java
index 87c9d52..4316ad3 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/RobotContainer.java
index 78b7f81..cc39207 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/RobotContainer.java
@@ -44,7 +44,7 @@
         new RunCommand(
             () ->
                 m_robotDrive.arcadeDrive(
-                    m_driverController.getLeftY(), m_driverController.getRightX()),
+                    -m_driverController.getLeftY(), m_driverController.getRightX()),
             m_robotDrive));
   }
 
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json
index c270fc4..ddf5d5e 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json
@@ -701,7 +701,8 @@
       "Sensors",
       "Simulation",
       "Physics",
-      "Mechanism2d"
+      "Mechanism2d",
+      "Preferences"
     ],
     "foldername": "armsimulation",
     "gradlebase": "java",
@@ -770,5 +771,27 @@
     "gradlebase": "javaromi",
     "mainclass": "Main",
     "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": "java",
+    "commandversion": 2,
+    "mainclass": "Main"
+  },
+  {
+    "name": "I2C Communication Sample",
+    "description": "An example program that communicates with external devices (such as an Arduino) using the roboRIO's I2C port",
+    "tags": [
+      "I2C"
+    ],
+    "foldername": "i2ccommunication",
+    "gradlebase": "java",
+    "commandversion": 2,
+    "mainclass": "Main"
   }
 ]
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/Robot.java
index a6b0023..a8d2d98 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/RobotContainer.java
index 5d228d0..1f00dd9 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/RobotContainer.java
@@ -67,7 +67,7 @@
         new RunCommand(
             () ->
                 m_robotDrive.arcadeDrive(
-                    m_driverController.getLeftY(), m_driverController.getRightX()),
+                    -m_driverController.getLeftY(), m_driverController.getRightX()),
             m_robotDrive));
   }
 
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/Robot.java
index 12fddb3..e9a1ae2 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Wrist.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Wrist.java
index f176316..e11e2d7 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Wrist.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Wrist.java
@@ -18,15 +18,11 @@
   private final Victor m_motor;
   private final AnalogPotentiometer m_pot;
 
-  private static final double kP_real = 1;
-  private static final double kP_simulation = 0.05;
+  private static final double kP = 1;
 
   /** Create a new wrist subsystem. */
   public Wrist() {
-    super(new PIDController(kP_real, 0, 0));
-    if (Robot.isSimulation()) { // Check for simulation and update PID values
-      getController().setPID(kP_simulation, 0, 0);
-    }
+    super(new PIDController(kP, 0, 0));
     getController().setTolerance(2.5);
 
     m_motor = new Victor(6);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java
index 0a9a2b0..f9499f5 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java
@@ -17,8 +17,9 @@
  * directory.
  */
 public class Robot extends TimedRobot {
-  private final DifferentialDrive m_robotDrive =
-      new DifferentialDrive(new PWMSparkMax(0), new PWMSparkMax(1));
+  private final PWMSparkMax m_leftDrive = new PWMSparkMax(0);
+  private final PWMSparkMax m_rightDrive = new PWMSparkMax(1);
+  private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftDrive, m_rightDrive);
   private final Joystick m_stick = new Joystick(0);
   private final Timer m_timer = new Timer();
 
@@ -27,7 +28,12 @@
    * initialization code.
    */
   @Override
-  public void robotInit() {}
+  public void robotInit() {
+    // 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_rightDrive.setInverted(true);
+  }
 
   /** This function is run once each time the robot enters autonomous mode. */
   @Override
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java
index 3d8353b..b0c6641 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java
@@ -28,14 +28,19 @@
   private static final int kGyroPort = 0;
   private static final int kJoystickPort = 0;
 
-  private final DifferentialDrive m_myRobot =
-      new DifferentialDrive(new PWMSparkMax(kLeftMotorPort), new PWMSparkMax(kRightMotorPort));
+  private final PWMSparkMax m_leftDrive = new PWMSparkMax(kLeftMotorPort);
+  private final PWMSparkMax m_rightDrive = new PWMSparkMax(kRightMotorPort);
+  private final DifferentialDrive m_myRobot = new DifferentialDrive(m_leftDrive, m_rightDrive);
   private final AnalogGyro m_gyro = new AnalogGyro(kGyroPort);
   private final Joystick m_joystick = new Joystick(kJoystickPort);
 
   @Override
   public void robotInit() {
     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_rightDrive.setInverted(true);
   }
 
   /**
@@ -47,6 +52,6 @@
     double turningValue = (kAngleSetpoint - m_gyro.getAngle()) * kP;
     // Invert the direction of the turn if we are going backwards
     turningValue = Math.copySign(turningValue, m_joystick.getY());
-    m_myRobot.arcadeDrive(m_joystick.getY(), turningValue);
+    m_myRobot.arcadeDrive(-m_joystick.getY(), turningValue);
   }
 }
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/Robot.java
index fff4d8c..bc6ede1 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/RobotContainer.java
index 1356a37..b70f5bf 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/RobotContainer.java
@@ -45,7 +45,7 @@
         new RunCommand(
             () ->
                 m_robotDrive.arcadeDrive(
-                    m_driverController.getLeftY(), m_driverController.getRightX()),
+                    -m_driverController.getLeftY(), m_driverController.getRightX()),
             m_robotDrive));
   }
 
@@ -74,7 +74,7 @@
                 // Setpoint is 0
                 0,
                 // Pipe the output to the turning controls
-                output -> m_robotDrive.arcadeDrive(m_driverController.getLeftY(), output),
+                output -> m_robotDrive.arcadeDrive(-m_driverController.getLeftY(), output),
                 // Require the robot drive
                 m_robotDrive));
 
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java
index f4b9a97..8b4391c 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java
@@ -11,8 +11,8 @@
 import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
 
 /**
- * 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).
+ * This is a sample program that uses mecanum drive with a gyro sensor to maintain rotation vectors
+ * in relation to the starting orientation of the robot (field-oriented controls).
  */
 public class Robot extends TimedRobot {
   // gyro calibration constant, may need to be adjusted;
@@ -37,10 +37,10 @@
     PWMSparkMax frontRight = new PWMSparkMax(kFrontRightChannel);
     PWMSparkMax rearRight = new PWMSparkMax(kRearRightChannel);
 
-    // Invert the left side motors.
+    // Invert the right side motors.
     // You may need to change or remove this to match your robot.
-    frontLeft.setInverted(true);
-    rearLeft.setInverted(true);
+    frontRight.setInverted(true);
+    rearRight.setInverted(true);
 
     m_robotDrive = new MecanumDrive(frontLeft, rearLeft, frontRight, rearRight);
 
@@ -51,6 +51,6 @@
   @Override
   public void teleopPeriodic() {
     m_robotDrive.driveCartesian(
-        m_joystick.getX(), m_joystick.getY(), m_joystick.getZ(), m_gyro.getAngle());
+        -m_joystick.getY(), m_joystick.getX(), m_joystick.getZ(), m_gyro.getAngle());
   }
 }
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/Robot.java
index 8f16ce5..ef49333 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java
index 2207379..cda9e26 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java
@@ -69,7 +69,7 @@
         new RunCommand(
             () ->
                 m_robotDrive.arcadeDrive(
-                    m_driverController.getLeftY(), m_driverController.getRightX()),
+                    -m_driverController.getLeftY(), m_driverController.getRightX()),
             m_robotDrive));
 
     // Add commands to the autonomous command chooser
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/Robot.java
index f6bcdcd..aa730c5 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/i2ccommunication/Main.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/i2ccommunication/Main.java
new file mode 100644
index 0000000..f981aeb
--- /dev/null
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/i2ccommunication/Main.java
@@ -0,0 +1,25 @@
+// 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.
+
+package edu.wpi.first.wpilibj.examples.i2ccommunication;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all. Unless you know what
+ * you are doing, do not modify this file except to change the parameter class to the startRobot
+ * call.
+ */
+public final class Main {
+  private Main() {}
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/i2ccommunication/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/i2ccommunication/Robot.java
new file mode 100644
index 0000000..9c1e623
--- /dev/null
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/i2ccommunication/Robot.java
@@ -0,0 +1,57 @@
+// 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.
+
+package edu.wpi.first.wpilibj.examples.i2ccommunication;
+
+import edu.wpi.first.wpilibj.DriverStation;
+import edu.wpi.first.wpilibj.I2C;
+import edu.wpi.first.wpilibj.TimedRobot;
+
+/**
+ * This is a sample program demonstrating how to communicate to a light controller from the robot
+ * code using the roboRIO's I2C port.
+ */
+public class Robot extends TimedRobot {
+  private static int kDeviceAddress = 4;
+
+  private static I2C m_arduino = new I2C(I2C.Port.kOnboard, kDeviceAddress);
+
+  private void writeString(String input) {
+    // Creates a char array from the input string
+    char[] chars = input.toCharArray();
+
+    // Creates a byte array from the char array
+    byte[] data = new byte[chars.length];
+
+    // Adds each character
+    for (int i = 0; i < chars.length; i++) {
+      data[i] = (byte) chars[i];
+    }
+
+    // Writes bytes over I2C
+    m_arduino.transaction(data, data.length, null, 0);
+  }
+
+  @Override
+  public void robotPeriodic() {
+    // 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.
+    StringBuilder stateMessage = new StringBuilder(6);
+
+    stateMessage
+        .append(DriverStation.getAlliance() == DriverStation.Alliance.Red ? "R" : "B")
+        .append(DriverStation.isEnabled() ? "E" : "D")
+        .append(DriverStation.isAutonomous() ? "A" : "T")
+        .append(String.format("%03d", (int) DriverStation.getMatchTime()));
+
+    writeString(stateMessage.toString());
+  }
+}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
index c660ae2..9210265 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumbot/Drivetrain.java
@@ -56,6 +56,11 @@
   /** Constructs a MecanumDrive and resets the gyro. */
   public 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);
   }
 
   /**
@@ -116,7 +121,7 @@
             fieldRelative
                 ? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeed, ySpeed, rot, m_gyro.getRotation2d())
                 : new ChassisSpeeds(xSpeed, ySpeed, rot));
-    mecanumDriveWheelSpeeds.normalize(kMaxSpeed);
+    mecanumDriveWheelSpeeds.desaturate(kMaxSpeed);
     setSpeeds(mecanumDriveWheelSpeeds);
   }
 
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Constants.java
index e959ac2..99962ee 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Constants.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Constants.java
@@ -55,8 +55,7 @@
     // 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.
+    // The SysId tool provides a convenient method for obtaining these values for your robot.
     public static final SimpleMotorFeedforward kFeedforward =
         new SimpleMotorFeedforward(1, 0.8, 0.15);
 
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Robot.java
index 3913f5d..527fe31 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
index 23da867..7874d82 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java
@@ -67,6 +67,11 @@
     m_rearLeftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
     m_frontRightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
     m_rearRightEncoder.setDistancePerPulse(DriveConstants.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);
   }
 
   @Override
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java
index 80c16b5..1029f0f 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java
@@ -28,10 +28,10 @@
     PWMSparkMax frontRight = new PWMSparkMax(kFrontRightChannel);
     PWMSparkMax rearRight = new PWMSparkMax(kRearRightChannel);
 
-    // Invert the left side motors.
+    // Invert the right side motors.
     // You may need to change or remove this to match your robot.
-    frontLeft.setInverted(true);
-    rearLeft.setInverted(true);
+    frontRight.setInverted(true);
+    rearRight.setInverted(true);
 
     m_robotDrive = new MecanumDrive(frontLeft, rearLeft, frontRight, rearRight);
 
@@ -42,6 +42,6 @@
   public void teleopPeriodic() {
     // 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(), 0.0);
+    m_robotDrive.driveCartesian(-m_stick.getY(), m_stick.getX(), m_stick.getZ(), 0.0);
   }
 }
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java
index ba544b2..427284f 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdriveposeestimator/Drivetrain.java
@@ -68,6 +68,11 @@
   /** Constructs a MecanumDrive and resets the gyro. */
   public 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);
   }
 
   /**
@@ -128,7 +133,7 @@
             fieldRelative
                 ? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeed, ySpeed, rot, m_gyro.getRotation2d())
                 : new ChassisSpeeds(xSpeed, ySpeed, rot));
-    mecanumDriveWheelSpeeds.normalize(kMaxSpeed);
+    mecanumDriveWheelSpeeds.desaturate(kMaxSpeed);
     setSpeeds(mecanumDriveWheelSpeeds);
   }
 
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Robot.java
index 49f1975..b072443 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java
index 680af28..5df8d2f 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java
@@ -53,7 +53,7 @@
         new RunCommand(
             () ->
                 m_robotDrive.arcadeDrive(
-                    m_driverController.getLeftY(), m_driverController.getRightX()),
+                    -m_driverController.getLeftY(), m_driverController.getRightX()),
             m_robotDrive));
   }
 
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java
index 8ca929d..b2fe2f7 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java
@@ -120,7 +120,7 @@
    */
   public void tankDriveVolts(double leftVolts, double rightVolts) {
     m_leftMotors.setVoltage(leftVolts);
-    m_rightMotors.setVoltage(-rightVolts);
+    m_rightMotors.setVoltage(rightVolts);
     m_drive.feed();
   }
 
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/Robot.java
index 0cd83a9..33e12b2 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/Robot.java
@@ -30,8 +30,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/schedulereventlogging/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/schedulereventlogging/Robot.java
index b61794c..f53d587 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/schedulereventlogging/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/schedulereventlogging/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/selectcommand/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/selectcommand/Robot.java
index 8bd49e8..1a89f2c 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/selectcommand/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/selectcommand/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java
index ea80fd2..986875a 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation/Drivetrain.java
@@ -144,8 +144,8 @@
     // simulated encoder and gyro. We negate the right side so that positive
     // voltages make the right side move forward.
     m_drivetrainSimulator.setInputs(
-        m_leftLeader.get() * RobotController.getInputVoltage(),
-        -m_rightLeader.get() * RobotController.getInputVoltage());
+        m_leftGroup.get() * RobotController.getInputVoltage(),
+        m_rightGroup.get() * RobotController.getInputVoltage());
     m_drivetrainSimulator.update(0.02);
 
     m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPositionMeters());
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java
index 5cbe38b..4636c37 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/RobotContainer.java
@@ -50,7 +50,7 @@
         new RunCommand(
             () ->
                 m_robotDrive.arcadeDrive(
-                    -m_driverController.getRightY(), m_driverController.getLeftX()),
+                    -m_driverController.getLeftY(), m_driverController.getRightX()),
             m_robotDrive));
   }
 
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java
index 98037c3..e974269 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java
@@ -122,7 +122,7 @@
     // move forward.
     m_drivetrainSimulator.setInputs(
         m_leftMotors.get() * RobotController.getBatteryVoltage(),
-        -m_rightMotors.get() * RobotController.getBatteryVoltage());
+        m_rightMotors.get() * RobotController.getBatteryVoltage());
     m_drivetrainSimulator.update(0.020);
 
     m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPositionMeters());
@@ -194,7 +194,7 @@
       rightVolts *= batteryVoltage / 12.0;
     }
     m_leftMotors.setVoltage(leftVolts);
-    m_rightMotors.setVoltage(-rightVolts);
+    m_rightMotors.setVoltage(rightVolts);
     m_drive.feed();
   }
 
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java
index 3575266..3b71a0c 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervebot/Drivetrain.java
@@ -53,7 +53,7 @@
             fieldRelative
                 ? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeed, ySpeed, rot, m_gyro.getRotation2d())
                 : new ChassisSpeeds(xSpeed, ySpeed, rot));
-    SwerveDriveKinematics.normalizeWheelSpeeds(swerveModuleStates, kMaxSpeed);
+    SwerveDriveKinematics.desaturateWheelSpeeds(swerveModuleStates, kMaxSpeed);
     m_frontLeft.setDesiredState(swerveModuleStates[0]);
     m_frontRight.setDesiredState(swerveModuleStates[1]);
     m_backLeft.setDesiredState(swerveModuleStates[2]);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Constants.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Constants.java
index b4e8e54..02c04b8 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Constants.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Constants.java
@@ -64,8 +64,7 @@
     // 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.
+    // The SysId tool provides a convenient method for obtaining these values for your robot.
     public static final double ksVolts = 1;
     public static final double kvVoltSecondsPerMeter = 0.8;
     public static final double kaVoltSecondsSquaredPerMeter = 0.15;
@@ -106,7 +105,7 @@
     public static final double kPYController = 1;
     public static final double kPThetaController = 1;
 
-    // Constraint for the motion profilied robot angle controller
+    // Constraint for the motion profiled robot angle controller
     public static final TrapezoidProfile.Constraints kThetaControllerConstraints =
         new TrapezoidProfile.Constraints(
             kMaxAngularSpeedRadiansPerSecond, kMaxAngularSpeedRadiansPerSecondSquared);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Robot.java
index 800b70f..ab57b74 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/RobotContainer.java
index a1a299a..4884a5d 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/RobotContainer.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/RobotContainer.java
@@ -42,16 +42,15 @@
     configureButtonBindings();
 
     // Configure default commands
-    // Set the default drive command to split-stick arcade drive
     m_robotDrive.setDefaultCommand(
-        // A split-stick arcade command, with forward/backward controlled by the left
-        // hand, and turning controlled by the right.
+        // The left stick controls translation of the robot.
+        // Turning is controlled by the X axis of the right stick.
         new RunCommand(
             () ->
                 m_robotDrive.drive(
                     m_driverController.getLeftY(),
-                    m_driverController.getRightX(),
                     m_driverController.getLeftX(),
+                    m_driverController.getRightX(),
                     false),
             m_robotDrive));
   }
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java
index 64d65b3..c0e364b 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java
@@ -68,8 +68,8 @@
     m_odometry.update(
         m_gyro.getRotation2d(),
         m_frontLeft.getState(),
-        m_rearLeft.getState(),
         m_frontRight.getState(),
+        m_rearLeft.getState(),
         m_rearRight.getState());
   }
 
@@ -106,7 +106,7 @@
             fieldRelative
                 ? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeed, ySpeed, rot, m_gyro.getRotation2d())
                 : new ChassisSpeeds(xSpeed, ySpeed, rot));
-    SwerveDriveKinematics.normalizeWheelSpeeds(
+    SwerveDriveKinematics.desaturateWheelSpeeds(
         swerveModuleStates, DriveConstants.kMaxSpeedMetersPerSecond);
     m_frontLeft.setDesiredState(swerveModuleStates[0]);
     m_frontRight.setDesiredState(swerveModuleStates[1]);
@@ -120,7 +120,7 @@
    * @param desiredStates The desired SwerveModule states.
    */
   public void setModuleStates(SwerveModuleState[] desiredStates) {
-    SwerveDriveKinematics.normalizeWheelSpeeds(
+    SwerveDriveKinematics.desaturateWheelSpeeds(
         desiredStates, DriveConstants.kMaxSpeedMetersPerSecond);
     m_frontLeft.setDesiredState(desiredStates[0]);
     m_frontRight.setDesiredState(desiredStates[1]);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java
index fd4c0b7..494d0ab 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/SwerveModule.java
@@ -36,22 +36,26 @@
   /**
    * Constructs a SwerveModule.
    *
-   * @param driveMotorChannel ID for the drive motor.
-   * @param turningMotorChannel ID for the turning motor.
+   * @param driveMotorChannel The channel of the drive motor.
+   * @param turningMotorChannel The channel of the turning motor.
+   * @param driveEncoderChannels The channels of the drive encoder.
+   * @param turningEncoderChannels The channels of the turning encoder.
+   * @param driveEncoderReversed Whether the drive encoder is reversed.
+   * @param turningEncoderReversed Whether the turning encoder is reversed.
    */
   public SwerveModule(
       int driveMotorChannel,
       int turningMotorChannel,
-      int[] driveEncoderPorts,
-      int[] turningEncoderPorts,
+      int[] driveEncoderChannels,
+      int[] turningEncoderChannels,
       boolean driveEncoderReversed,
       boolean turningEncoderReversed) {
     m_driveMotor = new Spark(driveMotorChannel);
     m_turningMotor = new Spark(turningMotorChannel);
 
-    this.m_driveEncoder = new Encoder(driveEncoderPorts[0], driveEncoderPorts[1]);
+    m_driveEncoder = new Encoder(driveEncoderChannels[0], driveEncoderChannels[1]);
 
-    this.m_turningEncoder = new Encoder(turningEncoderPorts[0], turningEncoderPorts[1]);
+    m_turningEncoder = new Encoder(turningEncoderChannels[0], turningEncoderChannels[1]);
 
     // Set the distance per pulse for the drive encoder. We can simply use the
     // distance traveled for one rotation of the wheel divided by the encoder
@@ -98,7 +102,7 @@
         m_drivePIDController.calculate(m_driveEncoder.getRate(), state.speedMetersPerSecond);
 
     // Calculate the turning motor output from the turning PID controller.
-    final var turnOutput =
+    final double turnOutput =
         m_turningPIDController.calculate(m_turningEncoder.get(), state.angle.getRadians());
 
     // Calculate the turning motor output from the turning PID controller.
@@ -106,7 +110,7 @@
     m_turningMotor.set(turnOutput);
   }
 
-  /** Zeros all the SwerveModule encoders. */
+  /** Zeroes all the SwerveModule encoders. */
   public void resetEncoders() {
     m_driveEncoder.reset();
     m_turningEncoder.reset();
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java
index 0e8feef..e1d16a0 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervedriveposeestimator/Drivetrain.java
@@ -65,7 +65,7 @@
             fieldRelative
                 ? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeed, ySpeed, rot, m_gyro.getRotation2d())
                 : new ChassisSpeeds(xSpeed, ySpeed, rot));
-    SwerveDriveKinematics.normalizeWheelSpeeds(swerveModuleStates, kMaxSpeed);
+    SwerveDriveKinematics.desaturateWheelSpeeds(swerveModuleStates, kMaxSpeed);
     m_frontLeft.setDesiredState(swerveModuleStates[0]);
     m_frontRight.setDesiredState(swerveModuleStates[1]);
     m_backLeft.setDesiredState(swerveModuleStates[2]);
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java
index f05e22c..c6a985a 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrivexboxcontroller/Robot.java
@@ -33,6 +33,6 @@
     // That means that the Y axis of the left stick moves the left side
     // of the robot forward and backward, and the Y axis of the right stick
     // moves the right side of the robot forward and backward.
-    m_robotDrive.tankDrive(m_driverController.getLeftY(), m_driverController.getRightY());
+    m_robotDrive.tankDrive(-m_driverController.getLeftY(), -m_driverController.getRightY());
   }
 }
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java
index 34cd3ce..8542096 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
@@ -92,4 +92,12 @@
   /** This function is called periodically during test mode. */
   @Override
   public void testPeriodic() {}
+
+  /** This function is called once when the robot is first started up. */
+  @Override
+  public void simulationInit() {}
+
+  /** This function is called periodically whilst in simulation. */
+  @Override
+  public void simulationPeriodic() {}
 }
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/Robot.java
index 2475ee6..fd39354 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/Robot.java
@@ -31,8 +31,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/subsystems/RomiDrivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/subsystems/RomiDrivetrain.java
index 80543c6..276e5ce 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/subsystems/RomiDrivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/subsystems/RomiDrivetrain.java
@@ -32,6 +32,9 @@
     m_leftEncoder.setDistancePerPulse((Math.PI * kWheelDiameterInch) / kCountsPerRevolution);
     m_rightEncoder.setDistancePerPulse((Math.PI * kWheelDiameterInch) / kCountsPerRevolution);
     resetEncoders();
+
+    // Invert right side since motor is flipped
+    m_rightMotor.setInverted(true);
   }
 
   public void arcadeDrive(double xaxisSpeed, double zaxisRotate) {
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/EducationalRobot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/EducationalRobot.java
new file mode 100644
index 0000000..8fed60d
--- /dev/null
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/EducationalRobot.java
@@ -0,0 +1,77 @@
+// 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.
+
+package edu.wpi.first.wpilibj.templates.romieducational;
+
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.DriverStation;
+import edu.wpi.first.wpilibj.RobotBase;
+
+/** Educational robot base class. */
+public class EducationalRobot extends RobotBase {
+  public void robotInit() {}
+
+  public void disabled() {}
+
+  public void run() {}
+
+  public void autonomous() {
+    run();
+  }
+
+  public void teleop() {
+    run();
+  }
+
+  public void test() {
+    run();
+  }
+
+  private volatile boolean m_exit;
+
+  @Override
+  public void startCompetition() {
+    robotInit();
+
+    // Tell the DS that the robot is ready to be enabled
+    HAL.observeUserProgramStarting();
+
+    while (!Thread.currentThread().isInterrupted() && !m_exit) {
+      if (isDisabled()) {
+        DriverStation.inDisabled(true);
+        disabled();
+        DriverStation.inDisabled(false);
+        while (isDisabled()) {
+          DriverStation.waitForData();
+        }
+      } else if (isAutonomous()) {
+        DriverStation.inAutonomous(true);
+        autonomous();
+        DriverStation.inAutonomous(false);
+        while (isAutonomousEnabled()) {
+          DriverStation.waitForData();
+        }
+      } else if (isTest()) {
+        DriverStation.inTest(true);
+        test();
+        DriverStation.inTest(false);
+        while (isTest() && isEnabled()) {
+          DriverStation.waitForData();
+        }
+      } else {
+        DriverStation.inTeleop(true);
+        teleop();
+        DriverStation.inTeleop(false);
+        while (isTeleopEnabled()) {
+          DriverStation.waitForData();
+        }
+      }
+    }
+  }
+
+  @Override
+  public void endCompetition() {
+    m_exit = true;
+  }
+}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/Main.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/Main.java
new file mode 100644
index 0000000..091543e
--- /dev/null
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/Main.java
@@ -0,0 +1,25 @@
+// 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.
+
+package edu.wpi.first.wpilibj.templates.romieducational;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all. Unless you know what
+ * you are doing, do not modify this file except to change the parameter class to the startRobot
+ * call.
+ */
+public final class Main {
+  private Main() {}
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/Robot.java
new file mode 100644
index 0000000..be58b72
--- /dev/null
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/Robot.java
@@ -0,0 +1,23 @@
+// 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.
+
+package edu.wpi.first.wpilibj.templates.romieducational;
+
+/**
+ * The VM is configured to automatically run this class, and to call the run() function when the
+ * robot is enabled. If you change the name of this class or the package after creating this
+ * project, you must also update the build.gradle file in the project.
+ */
+public class Robot extends EducationalRobot {
+  /**
+   * This function is run when the robot is first started up and should be used for any
+   * initialization code.
+   */
+  @Override
+  public void robotInit() {}
+
+  /** This function is run when the robot is enabled. */
+  @Override
+  public void run() {}
+}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/RomiDrivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/RomiDrivetrain.java
new file mode 100644
index 0000000..4b73a44
--- /dev/null
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romieducational/RomiDrivetrain.java
@@ -0,0 +1,58 @@
+// 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.
+
+package edu.wpi.first.wpilibj.templates.romieducational;
+
+import edu.wpi.first.wpilibj.Encoder;
+import edu.wpi.first.wpilibj.drive.DifferentialDrive;
+import edu.wpi.first.wpilibj.motorcontrol.Spark;
+
+public class RomiDrivetrain {
+  private static final double kCountsPerRevolution = 1440.0;
+  private static final double kWheelDiameterInch = 2.75591; // 70 mm
+
+  // The Romi has the left and right motors set to
+  // PWM channels 0 and 1 respectively
+  private final Spark m_leftMotor = new Spark(0);
+  private final Spark m_rightMotor = new Spark(1);
+
+  // The Romi has onboard encoders that are hardcoded
+  // to use DIO pins 4/5 and 6/7 for the left and right
+  private final Encoder m_leftEncoder = new Encoder(4, 5);
+  private final Encoder m_rightEncoder = new Encoder(6, 7);
+
+  // Set up the differential drive controller
+  private final DifferentialDrive m_diffDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
+
+  /** Creates a new RomiDrivetrain. */
+  public RomiDrivetrain() {
+    // Use inches as unit for encoder distances
+    m_leftEncoder.setDistancePerPulse((Math.PI * kWheelDiameterInch) / kCountsPerRevolution);
+    m_rightEncoder.setDistancePerPulse((Math.PI * kWheelDiameterInch) / kCountsPerRevolution);
+    resetEncoders();
+
+    // Invert right side since motor is flipped
+    m_rightMotor.setInverted(true);
+
+    // Disable motor safety
+    m_diffDrive.setSafetyEnabled(false);
+  }
+
+  public void arcadeDrive(double xaxisSpeed, double zaxisRotate) {
+    m_diffDrive.arcadeDrive(xaxisSpeed, zaxisRotate);
+  }
+
+  public void resetEncoders() {
+    m_leftEncoder.reset();
+    m_rightEncoder.reset();
+  }
+
+  public double getLeftDistanceInch() {
+    return m_leftEncoder.getDistance();
+  }
+
+  public double getRightDistanceInch() {
+    return m_rightEncoder.getDistance();
+  }
+}
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/Robot.java
index 75197ec..571bbc3 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/Robot.java
@@ -34,8 +34,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/RomiDrivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/RomiDrivetrain.java
index 96c81b1..e4f8559 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/RomiDrivetrain.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romitimed/RomiDrivetrain.java
@@ -31,6 +31,9 @@
     m_leftEncoder.setDistancePerPulse((Math.PI * kWheelDiameterInch) / kCountsPerRevolution);
     m_rightEncoder.setDistancePerPulse((Math.PI * kWheelDiameterInch) / kCountsPerRevolution);
     resetEncoders();
+
+    // Invert right side since motor is flipped
+    m_rightMotor.setInverted(true);
   }
 
   public void arcadeDrive(double xaxisSpeed, double zaxisRotate) {
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/templates.json b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/templates.json
index 9dd408f..b2484cc 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/templates.json
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/templates.json
@@ -1,5 +1,16 @@
 [
   {
+    "name": "Command Robot",
+    "description": "Command style",
+    "tags": [
+      "Command"
+    ],
+    "foldername": "commandbased",
+    "gradlebase": "java",
+    "mainclass": "Main",
+    "commandversion": 2
+  },
+  {
     "name": "Timed Robot",
     "description": "Timed style",
     "tags": [
@@ -14,7 +25,8 @@
     "name": "Timed Skeleton (Advanced)",
     "description": "Skeleton (stub) code for TimedRobot",
     "tags": [
-      "Timed", "Skeleton"
+      "Timed",
+      "Skeleton"
     ],
     "foldername": "timedskeleton",
     "gradlebase": "java",
@@ -25,7 +37,8 @@
     "name": "RobotBase Skeleton (Advanced)",
     "description": "Skeleton (stub) code for RobotBase",
     "tags": [
-      "RobotBase", "Skeleton"
+      "RobotBase",
+      "Skeleton"
     ],
     "foldername": "robotbaseskeleton",
     "gradlebase": "java",
@@ -33,13 +46,14 @@
     "commandversion": 2
   },
   {
-    "name": "Command Robot",
-    "description": "Command style",
+    "name": "Romi - Command Robot",
+    "description": "Romi - Command style",
     "tags": [
-      "Command"
+      "Command",
+      "Romi"
     ],
-    "foldername": "commandbased",
-    "gradlebase": "java",
+    "foldername": "romicommandbased",
+    "gradlebase": "javaromi",
     "mainclass": "Main",
     "commandversion": 2
   },
@@ -47,7 +61,8 @@
     "name": "Romi - Timed Robot",
     "description": "Romi - Timed style",
     "tags": [
-      "Timed", "Romi"
+      "Timed",
+      "Romi"
     ],
     "foldername": "romitimed",
     "gradlebase": "javaromi",
@@ -55,17 +70,6 @@
     "commandversion": 2
   },
   {
-    "name": "Romi - Command Robot",
-    "description": "Romi - Command style",
-    "tags": [
-      "Command", "Romi"
-    ],
-    "foldername": "romicommandbased",
-    "gradlebase": "javaromi",
-    "mainclass": "Main",
-    "commandversion": 2
-  },
-  {
     "name": "Educational Robot",
     "description": "Educational Robot - Not for competition use",
     "tags": [
@@ -75,5 +79,17 @@
     "gradlebase": "java",
     "mainclass": "Main",
     "commandversion": 2
+  },
+  {
+    "name": "Romi - Educational Robot",
+    "description": "Romi - Educational Robot",
+    "tags": [
+      "Educational",
+      "Romi"
+    ],
+    "foldername": "romieducational",
+    "gradlebase": "javaromi",
+    "mainclass": "Main",
+    "commandversion": 2
   }
 ]
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Robot.java
index 9141414..92b3075 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Robot.java
@@ -32,8 +32,8 @@
   }
 
   /**
-   * This function is called every robot packet, no matter the mode. Use this for items like
-   * diagnostics that you want ran during disabled, autonomous, teleoperated and test.
+   * 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.
    *
    * <p>This runs after the mode specific periodic functions, but before LiveWindow and
    * SmartDashboard integrated updating.
@@ -95,4 +95,12 @@
   /** This function is called periodically during test mode. */
   @Override
   public void testPeriodic() {}
+
+  /** This function is called once when the robot is first started up. */
+  @Override
+  public void simulationInit() {}
+
+  /** This function is called periodically whilst in simulation. */
+  @Override
+  public void simulationPeriodic() {}
 }
diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Robot.java
index d3968f3..4e0a8fe 100644
--- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Robot.java
+++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Robot.java
@@ -46,4 +46,10 @@
 
   @Override
   public void testPeriodic() {}
+
+  @Override
+  public void simulationInit() {}
+
+  @Override
+  public void simulationPeriodic() {}
 }