Skip to content
Draft
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
4 changes: 2 additions & 2 deletions .github/workflows/test.yml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ jobs:
runs-on: ${{ matrix.os }}
strategy:
matrix:
os: ["ubuntu-22.04", "macos-14", "windows-2022"]
os: ["ubuntu-24.04", "macos-14", "windows-2022"]
python_version:
- '3.9'
- '3.10'
Expand All @@ -37,7 +37,7 @@ jobs:
python-version: ${{ matrix.python_version }}
- name: Install deps
run: |
pip install 'robotpy[commands2,romi]<2026.0.0,>=2025.0.0b3' numpy pytest
pip install 'robotpy[commands2,romi]<2028,>=2027.0.0a2' numpy pytest
- name: Run tests
run: bash run_tests.sh
shell: bash
6 changes: 2 additions & 4 deletions AddressableLED/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,8 @@

class MyRobot(wpilib.TimedRobot):
def robotInit(self):
# PWM Port 9
# Must be a PWM header, not MXP or DIO
self.led = wpilib.AddressableLED(9)
# SmartIO port 1
self.led = wpilib.AddressableLED(1)

# LED Data
self.ledData = [wpilib.AddressableLED.LEDData() for _ in range(kLEDBuffer)]
Expand All @@ -28,7 +27,6 @@ def robotInit(self):

# Set the data
self.led.setData(self.ledData)
self.led.start()

def robotPeriodic(self):
# Fill the buffer with a rainbow
Expand Down
2 changes: 1 addition & 1 deletion ArmSimulation/physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ def __init__(self, physics_controller: PhysicsInterface, robot: "MyRobot"):
Constants.kArmEncoderDistPerPulse,
)
self.encoderSim = wpilib.simulation.EncoderSim(robot.arm.encoder)
self.motorSim = wpilib.simulation.PWMSim(robot.arm.motor.getChannel())
self.motorSim = wpilib.simulation.PWMMotorControllerSim(robot.arm.motor)

# Create a Mechanism2d display of an Arm with a fixed ArmTower and moving Arm.
self.mech2d = wpilib.Mechanism2d(60, 60)
Expand Down
2 changes: 1 addition & 1 deletion CANPDP/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ def robotInit(self):
"""Robot initialization function"""

# Object for dealing with the Power Distribution Panel (PDP).
self.pdp = wpilib.PowerDistribution()
self.pdp = wpilib.PowerDistribution(0)

# Put the PDP itself to the dashboard
wpilib.SmartDashboard.putData("PDP", self.pdp)
Expand Down
2 changes: 1 addition & 1 deletion DutyCycleInput/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ class MyRobot(wpilib.TimedRobot):
def robotInit(self):
"""Robot initialization function"""

self.dutyCycle = wpilib.DutyCycle(wpilib.DigitalInput(0))
self.dutyCycle = wpilib.DutyCycle(0)

def robotPeriodic(self):
# Duty Cycle Frequency in Hz
Expand Down
2 changes: 1 addition & 1 deletion ElevatorSimulation/physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ def __init__(self, physics_controller: PhysicsInterface, robot: "MyRobot"):
[0.01, 0.0],
)
self.encoderSim = wpilib.simulation.EncoderSim(robot.encoder)
self.motorSim = wpilib.simulation.PWMSim(robot.motor.getChannel())
self.motorSim = wpilib.simulation.PWMMotorControllerSim(robot.motor)

# Create a Mechanism2d display of an elevator
self.mech2d = wpilib.Mechanism2d(20, 50)
Expand Down
4 changes: 3 additions & 1 deletion FlywheelBangBangController/physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,9 @@ def __init__(self, physics_controller: PhysicsInterface, robot: "MyRobot"):
self.physics_controller = physics_controller

# Motors
self.flywheelMotor = wpilib.simulation.PWMSim(robot.flywheelMotor.getChannel())
self.flywheelMotor = wpilib.simulation.PWMMotorControllerSim(
robot.flywheelMotor.getChannel()
)

# Sensors
self.encoder = wpilib.simulation.EncoderSim(robot.encoder)
Expand Down
9 changes: 5 additions & 4 deletions GameData/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
import wpilib
import ntcore

CAN_BUS = 0
PNUE_MOD_TYPE = wpilib.PneumaticsModuleType.CTREPCM


Expand All @@ -18,10 +19,10 @@ class MyRobot(wpilib.TimedRobot):

def robotInit(self):
# A way of demonstrating the difference between the game data strings
self.blue = wpilib.Solenoid(PNUE_MOD_TYPE, 0)
self.red = wpilib.Solenoid(PNUE_MOD_TYPE, 1)
self.green = wpilib.Solenoid(PNUE_MOD_TYPE, 2)
self.yellow = wpilib.Solenoid(PNUE_MOD_TYPE, 3)
self.blue = wpilib.Solenoid(CAN_BUS, PNUE_MOD_TYPE, 0)
self.red = wpilib.Solenoid(CAN_BUS, PNUE_MOD_TYPE, 1)
self.green = wpilib.Solenoid(CAN_BUS, PNUE_MOD_TYPE, 2)
self.yellow = wpilib.Solenoid(CAN_BUS, PNUE_MOD_TYPE, 3)
# Set game data to empty string by default
self.gameData = ""
# Get the SmartDashboard table from networktables
Expand Down
4 changes: 2 additions & 2 deletions HatchbotInlined/physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,10 @@ def __init__(self, physics_controller: PhysicsInterface, robot: "MyRobot"):
self.physics_controller = physics_controller

# Motors
self.l_motor = wpilib.simulation.PWMSim(
self.l_motor = wpilib.simulation.PWMMotorControllerSim(
robot.container.driveSubsystem.left1.getChannel()
)
self.r_motor = wpilib.simulation.PWMSim(
self.r_motor = wpilib.simulation.PWMMotorControllerSim(
robot.container.driveSubsystem.right1.getChannel()
)

Expand Down
3 changes: 2 additions & 1 deletion HatchbotInlined/subsystems/hatchsubsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,10 @@ def __init__(self) -> None:
super().__init__()

self.hatchSolenoid = wpilib.DoubleSolenoid(
0,
constants.kHatchSolenoidModule,
constants.kHatchSolenoidModuleType,
*constants.kHatchSolenoidPorts
*constants.kHatchSolenoidPorts,
)

def grabHatch(self) -> commands2.Command:
Expand Down
4 changes: 2 additions & 2 deletions HatchbotTraditional/physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,10 +40,10 @@ def __init__(self, physics_controller: PhysicsInterface, robot: "MyRobot"):
self.physics_controller = physics_controller

# Motors
self.l_motor = wpilib.simulation.PWMSim(
self.l_motor = wpilib.simulation.PWMMotorControllerSim(
robot.container.drive.left1.getChannel()
)
self.r_motor = wpilib.simulation.PWMSim(
self.r_motor = wpilib.simulation.PWMMotorControllerSim(
robot.container.drive.right1.getChannel()
)

Expand Down
3 changes: 2 additions & 1 deletion HatchbotTraditional/subsystems/hatchsubsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,10 @@ def __init__(self) -> None:
super().__init__()

self.hatchSolenoid = wpilib.DoubleSolenoid(
0,
constants.kHatchSolenoidModule,
constants.kHatchSolenoidModuleType,
*constants.kHatchSolenoidPorts
*constants.kHatchSolenoidPorts,
)

def grabHatch(self) -> None:
Expand Down
6 changes: 3 additions & 3 deletions Physics/src/physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -38,14 +38,14 @@ def __init__(self, physics_controller: PhysicsInterface, robot: "MyRobot"):
self.physics_controller = physics_controller

# Motors
self.l_motor = wpilib.simulation.PWMSim(robot.l_motor.getChannel())
self.r_motor = wpilib.simulation.PWMSim(robot.r_motor.getChannel())
self.l_motor = wpilib.simulation.PWMMotorControllerSim(robot.l_motor)
self.r_motor = wpilib.simulation.PWMMotorControllerSim(robot.r_motor)

self.dio1 = wpilib.simulation.DIOSim(robot.limit1)
self.dio2 = wpilib.simulation.DIOSim(robot.limit2)
self.ain2 = wpilib.simulation.AnalogInputSim(robot.position)

self.motor = wpilib.simulation.PWMSim(robot.motor.getChannel())
self.motor = wpilib.simulation.PWMMotorControllerSim(robot.motor.getChannel())

# Gyro
self.gyro = wpilib.simulation.AnalogGyroSim(robot.gyro)
Expand Down
8 changes: 4 additions & 4 deletions Physics4Wheel/src/physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,10 @@ def __init__(self, physics_controller: PhysicsInterface, robot: "MyRobot"):
self.physics_controller = physics_controller

# Motors
self.lf_motor = wpilib.simulation.PWMSim(robot.lf_motor.getChannel())
# self.lr_motor = wpilib.simulation.PWMSim(2)
self.rf_motor = wpilib.simulation.PWMSim(robot.rf_motor.getChannel())
# self.rr_motor = wpilib.simulation.PWMSim(4)
self.lf_motor = wpilib.simulation.PWMMotorControllerSim(robot.lf_motor)
# self.lr_motor = wpilib.simulation.PWMMotorControllerSim(2)
self.rf_motor = wpilib.simulation.PWMMotorControllerSim(robot.rf_motor)
# self.rr_motor = wpilib.simulation.PWMMotorControllerSim(4)

# Gyro
self.gyro = wpilib.simulation.AnalogGyroSim(robot.gyro)
Expand Down
6 changes: 3 additions & 3 deletions PhysicsCamSim/src/physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#

from wpilib.simulation import (
PWMSim,
PWMMotorControllerSim,
DifferentialDrivetrainSim,
EncoderSim,
AnalogGyroSim,
Expand Down Expand Up @@ -79,8 +79,8 @@ def __init__(self, physics_controller: PhysicsInterface, robot: "MyRobot"):
)

# Create the motors.
self.l_motor = PWMSim(robot.leftMotor.getChannel())
self.r_motor = PWMSim(robot.rightMotor.getChannel())
self.l_motor = PWMMotorControllerSim(robot.leftMotor.getChannel())
self.r_motor = PWMMotorControllerSim(robot.rightMotor.getChannel())

self.gyroSim = AnalogGyroSim(robot.gyro)

Expand Down
8 changes: 4 additions & 4 deletions PhysicsMecanum/src/physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,10 +33,10 @@ def __init__(self, physics_controller: PhysicsInterface, robot: "MyRobot"):
self.physics_controller = physics_controller

# Motors
self.lf_motor = wpilib.simulation.PWMSim(robot.frontLeftMotor.getChannel())
self.lr_motor = wpilib.simulation.PWMSim(robot.rearLeftMotor.getChannel())
self.rf_motor = wpilib.simulation.PWMSim(robot.frontRightMotor.getChannel())
self.rr_motor = wpilib.simulation.PWMSim(robot.rearRightMotor.getChannel())
self.lf_motor = wpilib.simulation.PWMMotorControllerSim(robot.frontLeftMotor)
self.lr_motor = wpilib.simulation.PWMMotorControllerSim(robot.rearLeftMotor)
self.rf_motor = wpilib.simulation.PWMMotorControllerSim(robot.frontRightMotor)
self.rr_motor = wpilib.simulation.PWMMotorControllerSim(robot.rearRightMotor)

# Gyro
self.gyro = wpilib.simulation.AnalogGyroSim(robot.gyro)
Expand Down
6 changes: 3 additions & 3 deletions PhysicsSPI/src/physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,14 +44,14 @@ def __init__(self, physics_controller: PhysicsInterface, robot: "MyRobot"):
self.physics_controller = physics_controller

# Motors
self.l_motor = wpilib.simulation.PWMSim(robot.l_motor.getChannel())
self.r_motor = wpilib.simulation.PWMSim(robot.r_motor.getChannel())
self.l_motor = wpilib.simulation.PWMMotorControllerSim(robot.l_motor)
self.r_motor = wpilib.simulation.PWMMotorControllerSim(robot.r_motor)

self.dio1 = wpilib.simulation.DIOSim(robot.limit1)
self.dio2 = wpilib.simulation.DIOSim(robot.limit2)
self.ain2 = wpilib.simulation.AnalogInputSim(robot.position)

self.motor = wpilib.simulation.PWMSim(robot.motor.getChannel())
self.motor = wpilib.simulation.PWMMotorControllerSim(robot.motor.getChannel())

# Gyro
self.gyro = wpilib.simulation.ADXRS450_GyroSim(robot.gyro)
Expand Down
64 changes: 0 additions & 64 deletions RamseteCommand/constants.py

This file was deleted.

Loading
Loading