Skip to content
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
2 changes: 1 addition & 1 deletion examples/robot/ArcadeDriveXboxController/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ def __init__(self):
leftMotor = wpilib.PWMSparkMax(0)
rightMotor = wpilib.PWMSparkMax(1)
self.robotDrive = wpilib.DifferentialDrive(leftMotor, rightMotor)
self.driverController = wpilib.XboxController(0)
self.driverController = wpilib.NiDsXboxController(0)

# 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
Expand Down
2 changes: 1 addition & 1 deletion examples/robot/DifferentialDriveBot/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ class MyRobot(wpilib.TimedRobot):
def __init__(self) -> None:
super().__init__()

self.controller = wpilib.XboxController(0)
self.controller = wpilib.NiDsXboxController(0)
self.drive = Drivetrain()

# Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0 to 1.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ def __init__(self, cameraToObjectTopic: ntcore.DoubleArrayTopic) -> None:
# Simulation classes
self.leftEncoderSim = wpilib.simulation.EncoderSim(self.leftEncoder)
self.rightEncoderSim = wpilib.simulation.EncoderSim(self.rightEncoder)
self.drivetrainSystem = wpimath.LinearSystemId.identifyDrivetrainSystem(
self.drivetrainSystem = wpimath.Models.differentialDriveFromSysId(
1.98, 0.2, 1.5, 0.3
)
self.drivetrainSimulator = wpilib.simulation.DifferentialDrivetrainSim(
Expand Down
2 changes: 1 addition & 1 deletion examples/robot/DifferentialDrivePoseEstimator/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ def __init__(self) -> None:
self.inst = ntcore.NetworkTableInstance.getDefault()
self.doubleArrayTopic = self.inst.getDoubleArrayTopic("m_doubleArrayTopic")

self.controller = wpilib.XboxController(0)
self.controller = wpilib.NiDsXboxController(0)
self.drive = Drivetrain(self.doubleArrayTopic)

# Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0 to 1.
Expand Down
4 changes: 2 additions & 2 deletions examples/robot/DriveDistanceOffboard/robotcontainer.py
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ def __init__(self):
)

# The driver's controller
self.driverController = commands2.button.CommandXboxController(
self.driverController = commands2.button.CommandNiDsXboxController(
constants.OIConstants.kDriverControllerPort
)

Expand All @@ -58,7 +58,7 @@ def configureButtonBindings(self):
"""
Use this method to define your button->command mappings. Buttons can be created via the button
factories on commands2.button.CommandGenericHID or one of its
subclasses (commands2.button.CommandJoystick or command2.button.CommandXboxController).
subclasses (commands2.button.CommandJoystick or command2.button.CommandNiDsXboxController).
"""

# Configure your button bindings here
Expand Down
2 changes: 1 addition & 1 deletion examples/robot/FlywheelBangBangController/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ def __init__(self) -> None:

self.gearbox = wpimath.DCMotor.NEO(1)

self.plant = wpimath.LinearSystemId.flywheelSystem(
self.plant = wpimath.Models.flywheelFromPhysicalConstants(
self.gearbox, self.kFlywheelGearing, self.kFlywheelMomentOfInertia
)

Expand Down
2 changes: 1 addition & 1 deletion examples/robot/GettingStarted/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ def __init__(self):
self.leftDrive = wpilib.PWMSparkMax(0)
self.rightDrive = wpilib.PWMSparkMax(1)
self.robotDrive = wpilib.DifferentialDrive(self.leftDrive, self.rightDrive)
self.controller = wpilib.XboxController(0)
self.controller = wpilib.NiDsXboxController(0)
self.timer = wpilib.Timer()

# We need to invert one side of the drivetrain so that positive voltages
Expand Down
2 changes: 1 addition & 1 deletion examples/robot/HatchbotInlined/robotcontainer.py
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ def __init__(self) -> None:
)

# The driver's controller
self.driverController = commands2.button.CommandPS4Controller(
self.driverController = commands2.button.CommandNiDsPS4Controller(
constants.kDriverControllerPort
)

Expand Down
2 changes: 1 addition & 1 deletion examples/robot/HatchbotTraditional/robotcontainer.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ class RobotContainer:

def __init__(self) -> None:
# The driver's controller
# self.driverController = wpilib.XboxController(constants.kDriverControllerPort)
# self.driverController = wpilib.NiDsXboxController(constants.kDriverControllerPort)
self.driverController = wpilib.Joystick(constants.kDriverControllerPort)

# The robot's subsystems
Expand Down
10 changes: 5 additions & 5 deletions examples/robot/HidRumble/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,14 +17,14 @@ def __init__(self):
"""Robot initialization function"""
super().__init__()

self.hid = wpilib.XboxController(0)
self.hid = wpilib.NiDsXboxController(0)

def autonomousInit(self):
# Turn on rumble at the start of auto
self.hid.setRumble(wpilib.XboxController.RumbleType.kLeftRumble, 1.0)
self.hid.setRumble(wpilib.XboxController.RumbleType.kRightRumble, 1.0)
self.hid.setRumble(wpilib.NiDsXboxController.RumbleType.kLeftRumble, 1.0)
self.hid.setRumble(wpilib.NiDsXboxController.RumbleType.kRightRumble, 1.0)

def disabledInit(self):
# Stop the rumble when entering disabled
self.hid.setRumble(wpilib.XboxController.RumbleType.kLeftRumble, 0.0)
self.hid.setRumble(wpilib.XboxController.RumbleType.kRightRumble, 0.0)
self.hid.setRumble(wpilib.NiDsXboxController.RumbleType.kLeftRumble, 0.0)
self.hid.setRumble(wpilib.NiDsXboxController.RumbleType.kRightRumble, 0.0)
2 changes: 1 addition & 1 deletion examples/robot/MecanumBot/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ class MyRobot(wpilib.TimedRobot):
def __init__(self) -> None:
super().__init__()

self.controller = wpilib.XboxController(0)
self.controller = wpilib.NiDsXboxController(0)
self.mecanum = Drivetrain()

# Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0 to 1.
Expand Down
2 changes: 1 addition & 1 deletion examples/robot/MecanumDrivePoseEstimator/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ class MyRobot(wpilib.TimedRobot):
def __init__(self) -> None:
super().__init__()

self.controller = wpilib.XboxController(0)
self.controller = wpilib.NiDsXboxController(0)
self.mecanum = Drivetrain()

# Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0 to 1.
Expand Down
6 changes: 4 additions & 2 deletions examples/robot/RapidReactCommandBot/rapidreactcommandbot.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#

import commands2
from commands2.button import CommandXboxController, Trigger
from commands2.button import CommandNiDsXboxController, Trigger

from constants import AutoConstants, OIConstants, ShooterConstants
from subsystems.drive import Drive
Expand All @@ -31,7 +31,9 @@ def __init__(self) -> None:
self.pneumatics = Pneumatics()

# The driver's controller
self.driverController = CommandXboxController(OIConstants.kDriverControllerPort)
self.driverController = CommandNiDsXboxController(
OIConstants.kDriverControllerPort
)

def configureBindings(self) -> None:
"""Use this method to define bindings between conditions and commands. These are useful for
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ def __init__(self) -> None:
self.leftEncoderSim = wpilib.simulation.EncoderSim(self.leftEncoder)
self.rightEncoderSim = wpilib.simulation.EncoderSim(self.rightEncoder)
self.fieldSim = wpilib.Field2d()
self.drivetrainSystem = wpimath.LinearSystemId.identifyDrivetrainSystem(
self.drivetrainSystem = wpimath.Models.differentialDriveFromSysId(
1.98, 0.2, 1.5, 0.3
)
self.drivetrainSimulator = wpilib.simulation.DifferentialDrivetrainSim(
Expand Down
2 changes: 1 addition & 1 deletion examples/robot/SimpleDifferentialDriveSimulation/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
class MyRobot(wpilib.TimedRobot):
def __init__(self) -> None:
super().__init__()
self.controller = wpilib.XboxController(0)
self.controller = wpilib.NiDsXboxController(0)

# Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
# to 1.
Expand Down
2 changes: 1 addition & 1 deletion examples/robot/StateSpaceArm/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ def __init__(self) -> None:
# States: [position, velocity], in radians and radians per second.
# Inputs (what we can "put in"): [voltage], in volts.
# Outputs (what we can measure): [position], in radians.
self.armPlant = wpimath.LinearSystemId.singleJointedArmSystem(
self.armPlant = wpimath.Models.singleJointedArmFromPhysicalConstants(
wpimath.DCMotor.NEO(2),
kArmMOI,
kArmGearing,
Expand Down
2 changes: 1 addition & 1 deletion examples/robot/StateSpaceElevator/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ def __init__(self) -> None:
# Outputs (what we can measure): [position], in meters.

# This elevator is driven by two NEO motors.
self.elevatorPlant = wpimath.LinearSystemId.elevatorSystem(
self.elevatorPlant = wpimath.Models.elevatorFromPhysicalConstants(
wpimath.DCMotor.NEO(2),
kCarriageMass,
kDrumRadius,
Expand Down
2 changes: 1 addition & 1 deletion examples/robot/StateSpaceFlywheel/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ def __init__(self) -> None:
# States: [velocity], in radians per second.
# Inputs (what we can "put in"): [voltage], in volts.
# Outputs (what we can measure): [velocity], in radians per second.
self.flywheelPlant = wpimath.LinearSystemId.flywheelSystem(
self.flywheelPlant = wpimath.Models.flywheelFromPhysicalConstants(
wpimath.DCMotor.NEO(2),
kFlywheelMomentOfInertia,
kFlywheelGearing,
Expand Down
4 changes: 1 addition & 3 deletions examples/robot/StateSpaceFlywheelSysId/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,7 @@ def __init__(self) -> None:
# Outputs (what we can measure): [velocity], in radians per second.
#
# The Kv and Ka constants are found using the FRC Characterization toolsuite.
self.flywheelPlant = wpimath.LinearSystemId.identifyVelocitySystemRadians(
kFlywheelKv, kFlywheelKa
)
self.flywheelPlant = wpimath.Models.flywheelFromSysId(kFlywheelKv, kFlywheelKa)

# The observer fuses our encoder data and voltage inputs to reject noise.
self.observer = wpimath.KalmanFilter_1_1_1(
Expand Down
2 changes: 1 addition & 1 deletion examples/robot/SwerveBot/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ class MyRobot(wpilib.TimedRobot):
def __init__(self) -> None:
"""Robot initialization function"""
super().__init__()
self.controller = wpilib.XboxController(0)
self.controller = wpilib.NiDsXboxController(0)
self.swerve = drivetrain.Drivetrain()

# Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0 to 1.
Expand Down
2 changes: 1 addition & 1 deletion examples/robot/SwerveDrivePoseEstimator/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ class MyRobot(wpilib.TimedRobot):
def __init__(self) -> None:
super().__init__()

self.controller = wpilib.XboxController(0)
self.controller = wpilib.NiDsXboxController(0)
self.swerve = Drivetrain()

# Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0 to 1.
Expand Down
4 changes: 2 additions & 2 deletions examples/robot/SysId/sysidroutinebot.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#

from commands2 import Command
from commands2.button import CommandXboxController
from commands2.button import CommandNiDsXboxController
from commands2.sysid import SysIdRoutine

from subsystems.drive import Drive
Expand All @@ -27,7 +27,7 @@ def __init__(self) -> None:
self.shooter = Shooter()

# The driver's controller
self.controller = CommandXboxController(OIConstants.kDriverControllerPort)
self.controller = CommandNiDsXboxController(OIConstants.kDriverControllerPort)

def configureBindings(self) -> None:
"""Use this method to define bindings between conditions and commands. These are useful for
Expand Down
2 changes: 1 addition & 1 deletion examples/robot/TankDriveXboxController/robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ def __init__(self):
leftMotor = wpilib.PWMSparkMax(0)
rightMotor = wpilib.PWMSparkMax(1)
self.robotDrive = wpilib.DifferentialDrive(leftMotor, rightMotor)
self.driverController = wpilib.XboxController(0)
self.driverController = wpilib.NiDsXboxController(0)

# 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
Expand Down
2 changes: 1 addition & 1 deletion rdev.toml
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ wrapper = "2027.0.0a3"

[params]

wpilib_bin_version = "2027.0.0-alpha-3-192-g0fd8210b5"
wpilib_bin_version = "2027.0.0-alpha-3-212-g227c89ab2"
wpilib_bin_url = "https://frcmaven.wpi.edu/artifactory/development-2027"
# wpilib_bin_url = "https://frcmaven.wpi.edu/artifactory/development-2027"

Expand Down
6 changes: 0 additions & 6 deletions subprojects/robotpy-commands-v2/.gittrack

This file was deleted.

8 changes: 4 additions & 4 deletions subprojects/robotpy-commands-v2/commands2/button/__init__.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
from .commandgenerichid import CommandGenericHID
from .commandjoystick import CommandJoystick
from .commandps4controller import CommandPS4Controller
from .commandxboxcontroller import CommandXboxController
from .commandnidsps4controller import CommandNiDsPS4Controller
from .commandnidsxboxcontroller import CommandNiDsXboxController
from .joystickbutton import JoystickButton
from .networkbutton import NetworkButton
from .povbutton import POVButton
Expand All @@ -11,8 +11,8 @@
"Trigger",
"CommandGenericHID",
"CommandJoystick",
"CommandPS4Controller",
"CommandXboxController",
"CommandNiDsPS4Controller",
"CommandNiDsXboxController",
"JoystickButton",
"NetworkButton",
"POVButton",
Expand Down
Original file line number Diff line number Diff line change
@@ -1,19 +1,19 @@
# validated: 2024-01-20 DS d426873ed15b button/CommandPS4Controller.java
# validated: 2024-01-20 DS d426873ed15b button/CommandNiDsPS4Controller.java
from typing import Optional

from wpilib import EventLoop, PS4Controller
from wpilib import EventLoop, NiDsPS4Controller

from ..commandscheduler import CommandScheduler
from .commandgenerichid import CommandGenericHID
from .trigger import Trigger


class CommandPS4Controller(CommandGenericHID):
class CommandNiDsPS4Controller(CommandGenericHID):
"""
A version of PS4Controller with Trigger factories for command-based.
A version of NI DS PS4Controller with Trigger factories for command-based.
"""

_hid: PS4Controller
_hid: NiDsPS4Controller

def __init__(self, port: int):
"""
Expand All @@ -22,9 +22,9 @@ def __init__(self, port: int):
:param port: The port index on the Driver Station that the device is plugged into.
"""
super().__init__(port)
self._hid = PS4Controller(port)
self._hid = NiDsPS4Controller(port)

def getHID(self) -> PS4Controller:
def getHID(self) -> NiDsPS4Controller:
"""
Get the underlying GenericHID object.

Expand Down
Original file line number Diff line number Diff line change
@@ -1,19 +1,19 @@
# validated: 2024-01-20 DS 3ba501f9478a button/CommandXboxController.java
from typing import Optional

from wpilib import EventLoop, XboxController
from wpilib import EventLoop, NiDsXboxController

from ..commandscheduler import CommandScheduler
from .commandgenerichid import CommandGenericHID
from .trigger import Trigger


class CommandXboxController(CommandGenericHID):
class CommandNiDsXboxController(CommandGenericHID):
"""
A version of XboxController with Trigger factories for command-based.
A version of NI DS XboxController with Trigger factories for command-based.
"""

_hid: XboxController
_hid: NiDsXboxController

def __init__(self, port: int):
"""
Expand All @@ -22,9 +22,9 @@ def __init__(self, port: int):
:param port: The port index on the Driver Station that the controller is plugged into.
"""
super().__init__(port)
self._hid = XboxController(port)
self._hid = NiDsXboxController(port)

def getHID(self) -> XboxController:
def getHID(self) -> NiDsXboxController:
"""
Get the underlying GenericHID object.

Expand All @@ -44,7 +44,7 @@ def leftBumper(self, loop: Optional[EventLoop] = None) -> Trigger:
"""
if loop is None:
loop = CommandScheduler.getInstance().getDefaultButtonLoop()
return Trigger(loop, lambda: self._hid.getLeftBumper())
return Trigger(loop, lambda: self._hid.getLeftBumperButton())

def rightBumper(self, loop: Optional[EventLoop] = None) -> Trigger:
"""
Expand All @@ -58,7 +58,7 @@ def rightBumper(self, loop: Optional[EventLoop] = None) -> Trigger:
"""
if loop is None:
loop = CommandScheduler.getInstance().getDefaultButtonLoop()
return Trigger(loop, lambda: self._hid.getRightBumper())
return Trigger(loop, lambda: self._hid.getRightBumperButton())

def leftStick(self, loop: Optional[EventLoop] = None) -> Trigger:
"""
Expand Down
4 changes: 2 additions & 2 deletions subprojects/robotpy-cscore/pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ version_file = "cscore/version.py"
artifact_id = "cscore-cpp"
group_id = "org.wpilib.cscore"
repo_url = "https://frcmaven.wpi.edu/artifactory/development-2027"
version = "2027.0.0-alpha-3-192-g0fd8210b5"
version = "2027.0.0-alpha-3-212-g227c89ab2"

staticlibs = ["cscore"]
extract_to = "lib"
Expand All @@ -53,7 +53,7 @@ extract_to = "lib"
artifact_id = "cameraserver-cpp"
group_id = "org.wpilib.cameraserver"
repo_url = "https://frcmaven.wpi.edu/artifactory/development-2027"
version = "2027.0.0-alpha-3-192-g0fd8210b5"
version = "2027.0.0-alpha-3-212-g227c89ab2"

staticlibs = ["cameraserver"]
extract_to = "lib"
Expand Down
1 change: 1 addition & 0 deletions subprojects/robotpy-hal/semiwrap/DriverStation.yml
Original file line number Diff line number Diff line change
Expand Up @@ -43,3 +43,4 @@ functions:
HAL_ObserveUserProgram:
GetControlWord:
GetUncachedControlWord:
HAL_GetGameData:
Loading
Loading