diff --git a/.github/workflows/dist.yml b/.github/workflows/dist.yml
index b845df1..388fcdc 100644
--- a/.github/workflows/dist.yml
+++ b/.github/workflows/dist.yml
@@ -22,3 +22,14 @@ jobs:
       WPI_ARTIFACTORY_USERNAME: ${{ secrets.WPI_ARTIFACTORY_USERNAME }}
       WPI_ARTIFACTORY_TOKEN: ${{ secrets.WPI_ARTIFACTORY_TOKEN }}
       PYPI_API_TOKEN: ${{ secrets.PYPI_PASSWORD }}
+
+  check-example-headers:
+    runs-on: ubuntu-latest
+    steps:
+    - uses: actions/checkout@v4
+    - uses: actions/setup-python@v4
+      with:
+        python-version: 3.12
+    - name: Check header
+      run: python examples/check_header.py
+      shell: bash
diff --git a/examples/can-arcade-drive/robot.py b/examples/can-arcade-drive/robot.py
index 0c8e627..dbbd268 100644
--- a/examples/can-arcade-drive/robot.py
+++ b/examples/can-arcade-drive/robot.py
@@ -1,9 +1,9 @@
-# ----------------------------------------------------------------------------
-# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
-# Open Source Software - may be modified and shared by FRC teams. The code
-# must be accompanied by the FIRST BSD license file in the root directory of
-# the project.
-# ----------------------------------------------------------------------------
+#!/usr/bin/env python3
+#
+# 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.
+#
 
 import rev
 import wpilib
@@ -25,34 +25,60 @@ def robotInit(self):
         #
         # The example below initializes four brushless motors with CAN IDs
         # 1, 2, 3, 4. Change these parameters to match your setup
-        self.leftLeadMotor = rev.CANSparkMax(1, rev.CANSparkMax.MotorType.kBrushless)
-        self.rightLeadMotor = rev.CANSparkMax(3, rev.CANSparkMax.MotorType.kBrushless)
-        self.leftFollowMotor = rev.CANSparkMax(2, rev.CANSparkMax.MotorType.kBrushless)
-        self.rightFollowMotor = rev.CANSparkMax(4, rev.CANSparkMax.MotorType.kBrushless)
+        self.leftLeadMotor = rev.SparkMax(1, rev.SparkMax.MotorType.kBrushless)
+        self.rightLeadMotor = rev.SparkMax(3, rev.SparkMax.MotorType.kBrushless)
+        self.leftFollowMotor = rev.SparkMax(2, rev.SparkMax.MotorType.kBrushless)
+        self.rightFollowMotor = rev.SparkMax(4, rev.SparkMax.MotorType.kBrushless)
 
         # Passing in the lead motors into DifferentialDrive allows any
         # commmands sent to the lead motors to be sent to the follower motors.
         self.driveTrain = DifferentialDrive(self.leftLeadMotor, self.rightLeadMotor)
         self.joystick = wpilib.Joystick(0)
 
-        # The RestoreFactoryDefaults method can be used to reset the
-        # configuration parameters in the SPARK MAX to their factory default
-        # state. If no argument is passed, these parameters will not persist
-        # between power cycles
-        self.leftLeadMotor.restoreFactoryDefaults()
-        self.rightLeadMotor.restoreFactoryDefaults()
-        self.leftFollowMotor.restoreFactoryDefaults()
-        self.rightFollowMotor.restoreFactoryDefaults()
-
-        # In CAN mode, one SPARK MAX can be configured to follow another. This
-        # is done by calling the follow() method on the SPARK MAX you want to
-        # configure as a follower, and by passing as a parameter the SPARK MAX
-        # you want to configure as a leader.
+        # Create new SPARK MAX configuration objects. These will store the
+        # configuration parameters for the SPARK MAXes that we will set below.
+        self.globalConfig = rev.SparkMaxConfig()
+        self.rightLeaderConfig = rev.SparkMaxConfig()
+        self.leftFollowerConfig = rev.SparkMaxConfig()
+        self.rightFollowerConfig = rev.SparkMaxConfig()
+
+        # Apply the global config and invert since it is on the opposite side
+        self.rightLeaderConfig.apply(self.globalConfig).inverted(True)
+
+        # Apply the global config and set the leader SPARK for follower mode
+        self.leftFollowerConfig.apply(self.globalConfig).follow(self.leftLeadMotor)
+
+        # Apply the global config and set the leader SPARK for follower mode
+        self.rightFollowerConfig.apply(self.globalConfig).follow(self.rightLeadMotor)
+
+        # Apply the configuration to the SPARKs.
+        #
+        # kResetSafeParameters is used to get the SPARK MAX to a known state. This
+        # is useful in case the SPARK MAX is replaced.
         #
-        # This is shown in the example below, where one motor on each side of
-        # our drive train is configured to follow a lead motor.
-        self.leftFollowMotor.follow(self.leftLeadMotor)
-        self.rightFollowMotor.follow(self.rightLeadMotor)
+        # kPersistParameters is used to ensure the configuration is not lost when
+        # the SPARK MAX loses power. This is useful for power cycles that may occur
+        # mid-operation.
+        self.leftLeadMotor.configure(
+            self.globalConfig,
+            rev.SparkBase.ResetMode.kResetSafeParameters,
+            rev.SparkBase.PersistMode.kPersistParameters,
+        )
+        self.leftFollowMotor.configure(
+            self.leftFollowerConfig,
+            rev.SparkBase.ResetMode.kResetSafeParameters,
+            rev.SparkBase.PersistMode.kPersistParameters,
+        )
+        self.rightLeadMotor.configure(
+            self.rightLeaderConfig,
+            rev.SparkBase.ResetMode.kResetSafeParameters,
+            rev.SparkBase.PersistMode.kPersistParameters,
+        )
+        self.rightFollowMotor.configure(
+            self.rightFollowerConfig,
+            rev.SparkBase.ResetMode.kResetSafeParameters,
+            rev.SparkBase.PersistMode.kPersistParameters,
+        )
 
     def teleopPeriodic(self):
         # Drive with arcade style
diff --git a/examples/can-tank-drive/robot.py b/examples/can-tank-drive/robot.py
index 46035b0..01c2699 100644
--- a/examples/can-tank-drive/robot.py
+++ b/examples/can-tank-drive/robot.py
@@ -1,9 +1,9 @@
-# ----------------------------------------------------------------------------
-# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
-# Open Source Software - may be modified and shared by FRC teams. The code
-# must be accompanied by the FIRST BSD license file in the root directory of
-# the project.
-# ----------------------------------------------------------------------------
+#!/usr/bin/env python3
+#
+# 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.
+#
 
 import rev
 import wpilib
@@ -25,15 +25,22 @@ def robotInit(self):
         #
         # The example below initializes two brushless motors with CAN IDs
         # 1 and 2. Change these parameters to match your setup
-        self.leftMotor = rev.CANSparkMax(1, rev.CANSparkMax.MotorType.kBrushless)
-        self.rightMotor = rev.CANSparkMax(2, rev.CANSparkMax.MotorType.kBrushless)
-
-        # The RestoreFactoryDefaults method can be used to reset the
-        # configuration parameters in the SPARK MAX to their factory default
-        # state. If no argument is passed, these parameters will not persist
-        # between power cycles
-        self.leftMotor.restoreFactoryDefaults()
-        self.rightMotor.restoreFactoryDefaults()
+        self.leftMotor = rev.SparkMax(1, rev.SparkMax.MotorType.kBrushless)
+        self.rightMotor = rev.SparkMax(2, rev.SparkMax.MotorType.kBrushless)
+
+        # Configure for factory defaults and invert right side motor
+        self.globalConfig = rev.SparkMaxConfig()
+        self.rightConfig = self.globalConfig.inverted(True)
+        self.leftMotor.configure(
+            self.globalConfig,
+            rev.SparkBase.ResetMode.kResetSafeParameters,
+            rev.SparkBase.PersistMode.kPersistParameters,
+        )
+        self.rightMotor.configure(
+            self.rightConfig,
+            rev.SparkBase.ResetMode.kResetSafeParameters,
+            rev.SparkBase.PersistMode.kPersistParameters,
+        )
 
         self.driveTrain = DifferentialDrive(self.leftMotor, self.rightMotor)
         self.l_stick = wpilib.Joystick(0)
diff --git a/examples/check_header.py b/examples/check_header.py
new file mode 100644
index 0000000..66e39e3
--- /dev/null
+++ b/examples/check_header.py
@@ -0,0 +1,79 @@
+#!/usr/bin/env python3
+#
+# 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.
+#
+
+from pathlib import Path
+
+
+def check_file_content(file_path):
+    with open(file_path, "r") as file:
+        lines = file.readlines()
+
+        if file.name.endswith("robot.py"):
+            expected_lines = [
+                "#!/usr/bin/env python3\n",
+                "#\n",
+                "# Copyright (c) FIRST and other WPILib contributors.\n",
+                "# Open Source Software; you can modify and/or share it under the terms of\n",
+                "# the WPILib BSD license file in the root directory of this project.\n",
+                "#\n",
+                "\n",
+            ]
+        else:
+            expected_lines = [
+                "#\n",
+                "# Copyright (c) FIRST and other WPILib contributors.\n",
+                "# Open Source Software; you can modify and/or share it under the terms of\n",
+                "# the WPILib BSD license file in the root directory of this project.\n",
+                "#\n",
+                "\n",
+            ]
+
+        if lines[: len(expected_lines)] != expected_lines:
+            print(
+                "\n".join(
+                    [
+                        f"{file_path}",
+                        "ERROR: File must start with the following lines",
+                        "------------------------------",
+                        "".join(expected_lines[:-1]),
+                        "------------------------------",
+                        "Found:",
+                        "".join(lines[: len(expected_lines)]),
+                        "------------------------------",
+                    ]
+                )
+            )
+
+            return False
+    return True
+
+
+def main():
+    current_directory = Path(__file__).parent
+    python_files = [
+        x
+        for x in current_directory.glob("./**/*.py")
+        if not x.parent == current_directory and x.stat().st_size != 0
+    ]
+
+    non_compliant_files = [
+        file for file in python_files if not check_file_content(file)
+    ]
+
+    non_compliant_files.sort()
+
+    if non_compliant_files:
+        print("Non-compliant files:")
+        for file in non_compliant_files:
+            print(f"- {file}")
+        exit(1)  # Exit with an error code
+    else:
+        print("All files are compliant.")
+
+
+if __name__ == "__main__":
+    main()
diff --git a/examples/color_match/robot.py b/examples/color_match/robot.py
index 338c5b0..4d6c4cc 100644
--- a/examples/color_match/robot.py
+++ b/examples/color_match/robot.py
@@ -1,9 +1,9 @@
 #!/usr/bin/env python3
-
-# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
-# Open Source Software - may be modified and shared by FRC teams. The code
-# must be accompanied by the FIRST BSD license file in the root directory of
-# the project.
+#
+# 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.
+#
 
 import wpilib
 from rev import ColorSensorV3, ColorMatch
diff --git a/examples/get-set-params/robot.py b/examples/get-set-params/robot.py
index f501735..aa0b763 100644
--- a/examples/get-set-params/robot.py
+++ b/examples/get-set-params/robot.py
@@ -1,9 +1,9 @@
-# ----------------------------------------------------------------------------
-# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
-# Open Source Software - may be modified and shared by FRC teams. The code
-# must be accompanied by the FIRST BSD license file in the root directory of
-# the project.
-# ----------------------------------------------------------------------------
+#!/usr/bin/env python3
+#
+# 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.
+#
 
 import rev
 import wpilib
diff --git a/examples/getting-started/robot.py b/examples/getting-started/robot.py
index d531900..e662522 100755
--- a/examples/getting-started/robot.py
+++ b/examples/getting-started/robot.py
@@ -16,8 +16,8 @@ def robotInit(self):
         This function is called upon program startup and
         should be used for any initialization code.
         """
-        self.leftDrive = rev.CANSparkMax(1, rev.CANSparkMax.MotorType.kBrushless)
-        self.rightDrive = rev.CANSparkMax(2, rev.CANSparkMax.MotorType.kBrushless)
+        self.leftDrive = rev.SparkMax(1, rev.SparkMax.MotorType.kBrushless)
+        self.rightDrive = rev.SparkMax(2, rev.SparkMax.MotorType.kBrushless)
         self.robotDrive = wpilib.drive.DifferentialDrive(
             self.leftDrive, self.rightDrive
         )
diff --git a/examples/limit-switch/robot.py b/examples/limit-switch/robot.py
index aa4988c..f4a997a 100644
--- a/examples/limit-switch/robot.py
+++ b/examples/limit-switch/robot.py
@@ -1,9 +1,9 @@
-# ----------------------------------------------------------------------------
-# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
-# Open Source Software - may be modified and shared by FRC teams. The code
-# must be accompanied by the FIRST BSD license file in the root directory of
-# the project.
-# ----------------------------------------------------------------------------
+#!/usr/bin/env python3
+#
+# 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.
+#
 
 import rev
 import wpilib
@@ -16,33 +16,47 @@
 class Robot(wpilib.TimedRobot):
     def robotInit(self):
         # Create motor
-        self.motor = rev.CANSparkMax(1, rev.CANSparkMax.MotorType.kBrushless)
+        self.motor = rev.SparkMax(1, rev.SparkMax.MotorType.kBrushless)
 
         self.joystick = wpilib.Joystick(0)
 
-        # A CANDigitalInput object is constructed using the
-        # GetForwardLimitSwitch() or
-        # GetReverseLimitSwitch() method on an existing CANSparkMax object,
+        # A SparkLimitSwitch object is constructed using the
+        # getForwardLimitSwitch() or
+        # getReverseLimitSwitch() method on an existing CANSparkMax object,
         # depending on which direction you would like to limit
         #
         # Limit switches can be configured to one of two polarities:
-        # rev.CANDigitalInput.LimitSwitchPolarity.kNormallyOpen
-        # rev.CANDigitalInput.LimitSwitchPolarity.kNormallyClosed
-        self.forwardLimit = self.motor.getForwardLimitSwitch(
-            rev.SparkLimitSwitch.Type.kNormallyClosed
+        # rev.LimitSwitchConfig.Type.kNormallyOpen
+        # rev.LimitSwitchConfig.Type.kNormallyClosed
+        self.forwardLimit = self.motor.getForwardLimitSwitch()
+        self.reverseLimit = self.motor.getReverseLimitSwitch()
+
+        self.limitConfig = rev.SparkMaxConfig()
+        self.limitConfig.limitSwitch.forwardLimitSwitchType(
+            rev.LimitSwitchConfig.Type.kNormallyClosed
+        ).forwardLimitSwitchEnabled(False).reverseLimitSwitchType(
+            rev.LimitSwitchConfig.Type.kNormallyClosed
+        ).reverseLimitSwitchEnabled(
+            False
         )
-        self.reverseLimit = self.motor.getReverseLimitSwitch(
-            rev.SparkLimitSwitch.Type.kNormallyClosed
+        self.motor.configure(
+            self.limitConfig,
+            rev.SparkBase.ResetMode.kResetSafeParameters,
+            rev.SparkBase.PersistMode.kNoPersistParameters,
         )
 
-        self.forwardLimit.enableLimitSwitch(False)
-        self.reverseLimit.enableLimitSwitch(False)
+        self.prevForwardLimitEnabled = (
+            self.motor.configAccessor.limitSwitch.getForwardLimitSwitchEnabled()
+        )
+        self.prevReverseLimitEnabled = (
+            self.motor.configAccessor.limitSwitch.getReverseLimitSwitchEnabled()
+        )
 
         wpilib.SmartDashboard.putBoolean(
-            "Forward Limit Enabled", self.forwardLimit.isLimitSwitchEnabled()
+            "Forward Limit Enabled", self.prevForwardLimitEnabled
         )
         wpilib.SmartDashboard.putBoolean(
-            "Reverse Limit Enabled", self.forwardLimit.isLimitSwitchEnabled()
+            "Reverse Limit Enabled", self.prevReverseLimitEnabled
         )
 
     def teleopPeriodic(self):
@@ -50,14 +64,36 @@ def teleopPeriodic(self):
         self.motor.set(self.joystick.getY())
 
         # enable/disable limit switches based on value read from SmartDashboard
-        self.forwardLimit.enableLimitSwitch(
-            wpilib.SmartDashboard.getBoolean("Forward Limit Enabled", False)
-        )
-        self.reverseLimit.enableLimitSwitch(
-            wpilib.SmartDashboard.getBoolean("Reverse Limit Enabled", False)
-        )
+        if self.prevForwardLimitEnabled != wpilib.SmartDashboard.getBoolean(
+            "Forward Limit Enabled", False
+        ):
+            self.prevForwardLimitEnabled = wpilib.SmartDashboard.getBoolean(
+                "Forward Limit Enabled", False
+            )
+            self.limitConfig.limitSwitch.forwardLimitSwitchEnabled(
+                self.prevForwardLimitEnabled
+            )
+            self.motor.configure(
+                self.limitConfig,
+                rev.SparkBase.ResetMode.kResetSafeParameters,
+                rev.SparkBase.PersistMode.kNoPersistParameters,
+            )
+        if self.prevReverseLimitEnabled != wpilib.SmartDashboard.getBoolean(
+            "Reverse Limit Enabled", False
+        ):
+            self.prevReverseLimitEnabled = wpilib.SmartDashboard.getBoolean(
+                "Reverse Limit Enabled", False
+            )
+            self.limitConfig.limitSwitch.reverseLimitSwitchEnabled(
+                self.prevReverseLimitEnabled
+            )
+            self.motor.configure(
+                self.limitConfig,
+                rev.SparkBase.ResetMode.kResetSafeParameters,
+                rev.SparkBase.PersistMode.kNoPersistParameters,
+            )
 
-        # The get() method can be used on a CANDigitalInput object to read the
+        # The get() method can be used on a SparkLimitSwitch object to read the
         # state of the switch.
         #
         # In this example, the polarity of the switches are set to normally
diff --git a/examples/maxswerve/constants.py b/examples/maxswerve/constants.py
index 0c02876..3333d41 100644
--- a/examples/maxswerve/constants.py
+++ b/examples/maxswerve/constants.py
@@ -1,6 +1,8 @@
+#
 # 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.
+#
 
 """
 The constants module is a convenience place for teams to hold robot-wide
diff --git a/examples/maxswerve/robotcontainer.py b/examples/maxswerve/robotcontainer.py
index 1271e2c..7cfdca8 100644
--- a/examples/maxswerve/robotcontainer.py
+++ b/examples/maxswerve/robotcontainer.py
@@ -1,3 +1,9 @@
+#
+# 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.
+#
+
 import math
 
 import commands2
diff --git a/examples/maxswerve/subsystems/drivesubsystem.py b/examples/maxswerve/subsystems/drivesubsystem.py
index 732d1ca..76aa8b1 100644
--- a/examples/maxswerve/subsystems/drivesubsystem.py
+++ b/examples/maxswerve/subsystems/drivesubsystem.py
@@ -1,3 +1,9 @@
+#
+# 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.
+#
+
 import math
 import typing
 
diff --git a/examples/maxswerve/subsystems/maxswervemodule.py b/examples/maxswerve/subsystems/maxswervemodule.py
index 3579caf..959ca18 100644
--- a/examples/maxswerve/subsystems/maxswervemodule.py
+++ b/examples/maxswerve/subsystems/maxswervemodule.py
@@ -1,3 +1,9 @@
+#
+# 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.
+#
+
 from rev import CANSparkMax, SparkMaxAbsoluteEncoder
 from wpimath.geometry import Rotation2d
 from wpimath.kinematics import SwerveModuleState, SwerveModulePosition
diff --git a/examples/maxswerve/swerveutils.py b/examples/maxswerve/swerveutils.py
index ad6eccf..9f2df22 100644
--- a/examples/maxswerve/swerveutils.py
+++ b/examples/maxswerve/swerveutils.py
@@ -1,3 +1,9 @@
+#
+# 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.
+#
+
 import math
 
 
diff --git a/examples/position-pid-control/robot.py b/examples/position-pid-control/robot.py
index 5b09be8..0642475 100644
--- a/examples/position-pid-control/robot.py
+++ b/examples/position-pid-control/robot.py
@@ -1,9 +1,9 @@
-# ----------------------------------------------------------------------------
-# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
-# Open Source Software - may be modified and shared by FRC teams. The code
-# must be accompanied by the FIRST BSD license file in the root directory of
-# the project.
-# ----------------------------------------------------------------------------
+#!/usr/bin/env python3
+#
+# 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.
+#
 
 import rev
 import wpilib
diff --git a/examples/read-encoder-values/robot.py b/examples/read-encoder-values/robot.py
index 8059127..4ebbbb8 100644
--- a/examples/read-encoder-values/robot.py
+++ b/examples/read-encoder-values/robot.py
@@ -1,9 +1,9 @@
-# ----------------------------------------------------------------------------
-# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
-# Open Source Software - may be modified and shared by FRC teams. The code
-# must be accompanied by the FIRST BSD license file in the root directory of
-# the project.
-# ----------------------------------------------------------------------------
+#!/usr/bin/env python3
+#
+# 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.
+#
 
 import rev
 import wpilib
diff --git a/examples/read_rgb_values/robot.py b/examples/read_rgb_values/robot.py
index 534be3f..276f5a3 100755
--- a/examples/read_rgb_values/robot.py
+++ b/examples/read_rgb_values/robot.py
@@ -1,9 +1,9 @@
 #!/usr/bin/env python3
-
-# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
-# Open Source Software - may be modified and shared by FRC teams. The code
-# must be accompanied by the FIRST BSD license file in the root directory of
-# the project.
+#
+# 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.
+#
 
 import wpilib
 from rev import ColorSensorV3
diff --git a/examples/run_examples.py b/examples/run_examples.py
new file mode 100644
index 0000000..cbb65a5
--- /dev/null
+++ b/examples/run_examples.py
@@ -0,0 +1,43 @@
+import os
+import subprocess
+import sys
+
+BASE_TESTS = [
+    "can-arcade-drive",
+    "can-tank-drive",
+    "getting-started",
+    "limit-switch",
+]
+
+IGNORED_TESTS = [
+    "color_match",
+    "get-set-params",
+    "maxswerve",
+    "position-pid-control",
+    "read_rgb_values",
+    "read-encoder-values",
+    "smart-motion",
+    "velocity-pid-control",
+]  # Add ignored tests if any
+EVERY_TESTS = BASE_TESTS + IGNORED_TESTS
+TESTS = BASE_TESTS
+
+script_dir = os.path.dirname(__file__)
+
+robot_files = []
+for root, dirs, files in os.walk("."):
+    if "robot.py" in files:
+        robot_files.append(os.path.relpath(root, "."))
+
+for file in robot_files:
+    print("found: " + file)
+    if file not in EVERY_TESTS:
+        if not os.getenv("FORCE_ANYWAYS"):
+            print("ERROR: Not every robot.py file is in the list of tests!")
+            exit(1)
+
+for test in TESTS:
+    print(f"Running test: {test}")
+    os.chdir(os.path.join(script_dir, test))
+    subprocess.run([sys.executable, "-m", "robotpy", "test", "--builtin"])
+    os.chdir(script_dir)
diff --git a/examples/smart-motion/robot.py b/examples/smart-motion/robot.py
index 751aa9a..fb4505a 100755
--- a/examples/smart-motion/robot.py
+++ b/examples/smart-motion/robot.py
@@ -1,10 +1,9 @@
 #!/usr/bin/env python3
-# ----------------------------------------------------------------------------
-# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
-# Open Source Software - may be modified and shared by FRC teams. The code
-# must be accompanied by the FIRST BSD license file in the root directory of
-# the project.
-# ----------------------------------------------------------------------------
+#
+# 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.
+#
 
 import rev
 import wpilib
diff --git a/examples/velocity-pid-control/robot.py b/examples/velocity-pid-control/robot.py
index 86735e3..b8649b3 100644
--- a/examples/velocity-pid-control/robot.py
+++ b/examples/velocity-pid-control/robot.py
@@ -1,9 +1,9 @@
-# ----------------------------------------------------------------------------
-# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
-# Open Source Software - may be modified and shared by FRC teams. The code
-# must be accompanied by the FIRST BSD license file in the root directory of
-# the project.
-# ----------------------------------------------------------------------------
+#!/usr/bin/env python3
+#
+# 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.
+#
 
 import rev
 import wpilib
diff --git a/tests/requirements.txt b/tests/requirements.txt
index e079f8a..2777db4 100644
--- a/tests/requirements.txt
+++ b/tests/requirements.txt
@@ -1 +1,2 @@
 pytest
+robotpy
diff --git a/tests/run_tests.py b/tests/run_tests.py
index 2ffc659..58ba800 100755
--- a/tests/run_tests.py
+++ b/tests/run_tests.py
@@ -10,3 +10,5 @@
     os.chdir(root)
 
     subprocess.check_call([sys.executable, "-m", "pytest"])
+
+    subprocess.check_call([sys.executable, "../examples/run_examples.py"])