Skip to content

Update examples for 2024 #78

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 1 commit into from
Dec 1, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 10 additions & 7 deletions .github/workflows/test.yml
Original file line number Diff line number Diff line change
Expand Up @@ -13,28 +13,31 @@ jobs:
check:
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v3
- uses: actions/checkout@v4
- uses: psf/black@stable

test:
runs-on: ${{ matrix.os }}
strategy:
matrix:
os: [windows-latest, macos-latest, ubuntu-22.04]
python_version: [3.7, 3.8, 3.9, "3.10", "3.11"]
os: ["ubuntu-22.04", "macos-12", "windows-2022"]
python_version:
# - '3.8'
# - '3.9'
- '3.10'
- '3.11'
- '3.12'

steps:
- uses: actions/checkout@v3
- uses: actions/checkout@v4
- uses: actions/setup-python@v4
with:
python-version: ${{ matrix.python_version }}
architecture: ${{ matrix.architecture }}
- name: Install deps
run: |
pip install numpy
pip install -U pip
pip install 'robotpy[commands2]<2024.0.0,>=2023.1.1.0' pytest
#pip install 'robotpy[commands2,romi]<2024.0.0,>=2023.0.0b3' pytest
pip install 'robotpy[commands2]<2025.0.0,>=2024.0.0b3' numpy pytest
- name: Run tests
run: bash run_tests.sh
shell: bash
1 change: 1 addition & 0 deletions arm-simulation/physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@ def __init__(self, physics_controller: PhysicsInterface, robot: "MyRobot"):
math.radians(-75),
math.radians(255),
True,
0,
)
self.encoderSim = wpilib.simulation.EncoderSim(robot.encoder)
self.motorSim = wpilib.simulation.PWMSim(robot.motor.getChannel())
Expand Down
2 changes: 1 addition & 1 deletion commands-v2/armbot/subsystems/drivesubsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
import constants


class DriveSubsystem(commands2.SubsystemBase):
class DriveSubsystem(commands2.Subsystem):
# Creates a new DriveSubsystem
def __init__(self) -> None:
super().__init__()
Expand Down
2 changes: 1 addition & 1 deletion commands-v2/armbotoffboard/subsystems/drivesubsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
import typing


class DriveSubsystem(commands2.SubsystemBase):
class DriveSubsystem(commands2.Subsystem):
def __init__(self) -> None:
super().__init__()

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
import examplesmartmotorcontroller


class DriveSubsystem(commands2.SubsystemBase):
class DriveSubsystem(commands2.Subsystem):
def __init__(self) -> None:
"""Creates a new DriveSubsystem"""
super().__init__()
Expand Down
2 changes: 1 addition & 1 deletion commands-v2/frisbee-bot/subsystems/drivesubsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
import constants


class DriveSubsystem(commands2.SubsystemBase):
class DriveSubsystem(commands2.Subsystem):
def __init__(self) -> None:
"""Creates a new DriveSubsystem"""
super().__init__()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
import constants


class DriveSubsystem(commands2.SubsystemBase):
class DriveSubsystem(commands2.Subsystem):
def __init__(self) -> None:
"""Creates a new DriveSubsystem"""
super().__init__()
Expand Down
64 changes: 32 additions & 32 deletions commands-v2/hatchbot-inlined/commands/autos.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ class Autos:
def __init__(self) -> None:
raise Exception("This is a utility class!")

@staticmethod
def simpleAuto(drive: subsystems.drivesubsystem.DriveSubsystem):
"""A simple auto routine that drives forward a specified distance, and then stops."""
return commands2.FunctionalCommand(
Expand All @@ -35,42 +36,41 @@ def simpleAuto(drive: subsystems.drivesubsystem.DriveSubsystem):
# Require the drive subsystem
)

@staticmethod
def complexAuto(
driveSubsystem: subsystems.drivesubsystem.DriveSubsystem,
hatchSubsystem: subsystems.hatchsubsystem.HatchSubsystem,
):
"""A complex auto routine that drives forward, drops a hatch, and then drives backward."""
return commands2.cmd.sequence(
[
# Drive forward up to the front of the cargo ship
commands2.FunctionalCommand(
# Reset encoders on command start
driveSubsystem.resetEncoders,
# Drive forward while the command is executing
lambda: driveSubsystem.arcadeDrive(constants.kAutoDriveSpeed, 0),
# Stop driving at the end of the command
lambda interrupt: driveSubsystem.arcadeDrive(0, 0),
# End the command when the robot's driven distance exceeds the desired value
lambda: driveSubsystem.getAverageEncoderDistance()
>= constants.kAutoDriveDistanceInches,
# Require the drive subsystem
[driveSubsystem],
),
# Release the hatch
hatchSubsystem.releaseHatch(),
# Drive backward the specified distance
commands2.FunctionalCommand(
# Reset encoders on command start
driveSubsystem.resetEncoders,
# Drive backwards while the command is executing
lambda: driveSubsystem.arcadeDrive(-constants.kAutoDriveSpeed, 0),
# Stop driving at the end of the command
lambda interrupt: driveSubsystem.arcadeDrive(0, 0),
# End the command when the robot's driven distance exceeds the desired value
lambda: abs(driveSubsystem.getAverageEncoderDistance())
>= constants.kAutoBackupDistanceInches,
# Require the drive subsystem
[driveSubsystem],
),
]
# Drive forward up to the front of the cargo ship
commands2.FunctionalCommand(
# Reset encoders on command start
driveSubsystem.resetEncoders,
# Drive forward while the command is executing
lambda: driveSubsystem.arcadeDrive(constants.kAutoDriveSpeed, 0),
# Stop driving at the end of the command
lambda interrupt: driveSubsystem.arcadeDrive(0, 0),
# End the command when the robot's driven distance exceeds the desired value
lambda: driveSubsystem.getAverageEncoderDistance()
>= constants.kAutoDriveDistanceInches,
# Require the drive subsystem
driveSubsystem,
),
# Release the hatch
hatchSubsystem.releaseHatch(),
# Drive backward the specified distance
commands2.FunctionalCommand(
# Reset encoders on command start
driveSubsystem.resetEncoders,
# Drive backwards while the command is executing
lambda: driveSubsystem.arcadeDrive(-constants.kAutoDriveSpeed, 0),
# Stop driving at the end of the command
lambda interrupt: driveSubsystem.arcadeDrive(0, 0),
# End the command when the robot's driven distance exceeds the desired value
lambda: abs(driveSubsystem.getAverageEncoderDistance())
>= constants.kAutoBackupDistanceInches,
# Require the drive subsystem
driveSubsystem,
),
)
3 changes: 1 addition & 2 deletions commands-v2/hatchbot-inlined/physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,7 @@

import wpilib
import wpilib.simulation
from wpimath.system import LinearSystemId
from wpimath.system.plant import DCMotor
from wpimath.system.plant import DCMotor, LinearSystemId

import constants

Expand Down
2 changes: 1 addition & 1 deletion commands-v2/hatchbot-inlined/robotcontainer.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ def __init__(self) -> None:
-self.driverController.getLeftY(),
-self.driverController.getRightX(),
),
[self.driveSubsystem],
self.driveSubsystem,
)
)

Expand Down
2 changes: 1 addition & 1 deletion commands-v2/hatchbot-inlined/subsystems/drivesubsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
import constants


class DriveSubsystem(commands2.SubsystemBase):
class DriveSubsystem(commands2.Subsystem):
def __init__(self) -> None:
super().__init__()

Expand Down
6 changes: 3 additions & 3 deletions commands-v2/hatchbot-inlined/subsystems/hatchsubsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
import constants


class HatchSubsystem(commands2.SubsystemBase):
class HatchSubsystem(commands2.Subsystem):
def __init__(self) -> None:
super().__init__()

Expand All @@ -18,11 +18,11 @@ def __init__(self) -> None:
def grabHatch(self) -> commands2.Command:
"""Grabs the hatch"""
return commands2.cmd.runOnce(
lambda: self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.kForward), [self]
lambda: self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.kForward), self
)

def releaseHatch(self) -> commands2.Command:
"""Releases the hatch"""
return commands2.cmd.runOnce(
lambda: self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.kReverse), [self]
lambda: self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.kReverse), self
)
4 changes: 2 additions & 2 deletions commands-v2/hatchbot/commands/defaultdrive.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
from subsystems.drivesubsystem import DriveSubsystem


class DefaultDrive(commands2.CommandBase):
class DefaultDrive(commands2.Command):
def __init__(
self,
drive: DriveSubsystem,
Expand All @@ -16,7 +16,7 @@ def __init__(
self.forward = forward
self.rotation = rotation

self.addRequirements([self.drive])
self.addRequirements(self.drive)

def execute(self) -> None:
self.drive.arcadeDrive(self.forward(), self.rotation())
2 changes: 1 addition & 1 deletion commands-v2/hatchbot/commands/drivedistance.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
from subsystems.drivesubsystem import DriveSubsystem


class DriveDistance(commands2.CommandBase):
class DriveDistance(commands2.Command):
def __init__(self, inches: float, speed: float, drive: DriveSubsystem) -> None:
super().__init__()
self.distance = inches
Expand Down
2 changes: 1 addition & 1 deletion commands-v2/hatchbot/commands/grabhatch.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
from subsystems.hatchsubsystem import HatchSubsystem


class GrabHatch(commands2.CommandBase):
class GrabHatch(commands2.Command):
def __init__(self, hatch: HatchSubsystem) -> None:
super().__init__()
self.hatch = hatch
Expand Down
2 changes: 1 addition & 1 deletion commands-v2/hatchbot/commands/halvedrivespeed.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
from subsystems.drivesubsystem import DriveSubsystem


class HalveDriveSpeed(commands2.CommandBase):
class HalveDriveSpeed(commands2.Command):
def __init__(self, drive: DriveSubsystem) -> None:
super().__init__()
self.drive = drive
Expand Down
3 changes: 1 addition & 2 deletions commands-v2/hatchbot/physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,7 @@

import wpilib
import wpilib.simulation
from wpimath.system import LinearSystemId
from wpimath.system.plant import DCMotor
from wpimath.system.plant import DCMotor, LinearSystemId

import constants

Expand Down
6 changes: 3 additions & 3 deletions commands-v2/hatchbot/robotcontainer.py
Original file line number Diff line number Diff line change
Expand Up @@ -72,15 +72,15 @@ def configureButtonBindings(self):
and then passing it to a JoystickButton.
"""

commands2.button.JoystickButton(self.driverController, 1).whenPressed(
commands2.button.JoystickButton(self.driverController, 1).onTrue(
GrabHatch(self.hatch)
)

commands2.button.JoystickButton(self.driverController, 2).whenPressed(
commands2.button.JoystickButton(self.driverController, 2).onTrue(
ReleaseHatch(self.hatch)
)

commands2.button.JoystickButton(self.driverController, 3).whenHeld(
commands2.button.JoystickButton(self.driverController, 3).whileTrue(
HalveDriveSpeed(self.drive)
)

Expand Down
2 changes: 1 addition & 1 deletion commands-v2/hatchbot/subsystems/drivesubsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
import constants


class DriveSubsystem(commands2.SubsystemBase):
class DriveSubsystem(commands2.Subsystem):
def __init__(self) -> None:
super().__init__()

Expand Down
2 changes: 1 addition & 1 deletion commands-v2/hatchbot/subsystems/hatchsubsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
import constants


class HatchSubsystem(commands2.SubsystemBase):
class HatchSubsystem(commands2.Subsystem):
def __init__(self) -> None:
super().__init__()

Expand Down
4 changes: 2 additions & 2 deletions commands-v2/ramsete/subsystems/drivetrain.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
from commands2 import SubsystemBase
from commands2 import Subsystem

from wpilib import MotorControllerGroup, PWMSparkMax, Encoder, AnalogGyro
from wpilib.drive import DifferentialDrive
Expand All @@ -9,7 +9,7 @@
import constants


class Drivetrain(SubsystemBase):
class Drivetrain(Subsystem):
def __init__(self):
super().__init__()

Expand Down
2 changes: 1 addition & 1 deletion commands-v2/romi/commands/arcadedrive.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
from subsystems.drivetrain import Drivetrain


class ArcadeDrive(commands2.CommandBase):
class ArcadeDrive(commands2.Command):
def __init__(
self,
drive: Drivetrain,
Expand Down
2 changes: 1 addition & 1 deletion commands-v2/romi/commands/drivedistance.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
from subsystems.drivetrain import Drivetrain


class DriveDistance(commands2.CommandBase):
class DriveDistance(commands2.Command):
def __init__(self, speed: float, inches: float, drive: Drivetrain) -> None:
"""Creates a new DriveDistance. This command will drive your your robot for a desired distance at
a desired speed.
Expand Down
2 changes: 1 addition & 1 deletion commands-v2/romi/commands/drivetime.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
from subsystems.drivetrain import Drivetrain


class DriveTime(commands2.CommandBase):
class DriveTime(commands2.Command):
"""Creates a new DriveTime. This command will drive your robot for a desired speed and time."""

def __init__(self, speed: float, time: float, drive: Drivetrain) -> None:
Expand Down
2 changes: 1 addition & 1 deletion commands-v2/romi/commands/turndegrees.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
from subsystems.drivetrain import Drivetrain


class TurnDegrees(commands2.CommandBase):
class TurnDegrees(commands2.Command):
def __init__(self, speed: float, degrees: float, drive: Drivetrain) -> None:
"""Creates a new TurnDegrees. This command will turn your robot for a desired rotation (in
degrees) and rotational speed.
Expand Down
2 changes: 1 addition & 1 deletion commands-v2/romi/commands/turntime.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
from subsystems.drivetrain import Drivetrain


class TurnTime(commands2.CommandBase):
class TurnTime(commands2.Command):
"""Creates a new TurnTime command. This command will turn your robot for a
desired rotational speed and time.
"""
Expand Down
2 changes: 1 addition & 1 deletion commands-v2/romi/robotcontainer.py
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ def _configureButtonBindings(self):
self.chooser.addOption("Auto Routine Time", AutonomousTime(self.drivetrain))
wpilib.SmartDashboard.putData(self.chooser)

def getAutonomousCommand(self) -> typing.Optional[commands2.CommandBase]:
def getAutonomousCommand(self) -> typing.Optional[commands2.Command]:
return self.chooser.getSelected()

def getArcadeDriveCommand(self) -> ArcadeDrive:
Expand Down
2 changes: 1 addition & 1 deletion commands-v2/romi/subsystems/drivetrain.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
import romi


class Drivetrain(commands2.SubsystemBase):
class Drivetrain(commands2.Subsystem):
kCountsPerRevolution = 1440.0
kWheelDiameterInch = 2.75591

Expand Down
Loading