Skip to content

Commit

Permalink
Merge pull request #74 from sciencewhiz/AddTests
Browse files Browse the repository at this point in the history
Add testing for examples
  • Loading branch information
virtuald authored Jan 27, 2025
2 parents 384ca50 + 8566962 commit b2d0024
Show file tree
Hide file tree
Showing 21 changed files with 341 additions and 111 deletions.
11 changes: 11 additions & 0 deletions .github/workflows/dist.yml
Original file line number Diff line number Diff line change
Expand Up @@ -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
80 changes: 53 additions & 27 deletions examples/can-arcade-drive/robot.py
Original file line number Diff line number Diff line change
@@ -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
Expand All @@ -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
Expand Down
37 changes: 22 additions & 15 deletions examples/can-tank-drive/robot.py
Original file line number Diff line number Diff line change
@@ -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
Expand All @@ -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)
Expand Down
79 changes: 79 additions & 0 deletions examples/check_header.py
Original file line number Diff line number Diff line change
@@ -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()
10 changes: 5 additions & 5 deletions examples/color_match/robot.py
Original file line number Diff line number Diff line change
@@ -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
Expand Down
12 changes: 6 additions & 6 deletions examples/get-set-params/robot.py
Original file line number Diff line number Diff line change
@@ -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
Expand Down
4 changes: 2 additions & 2 deletions examples/getting-started/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
)
Expand Down
Loading

0 comments on commit b2d0024

Please sign in to comment.