[robotpy][examples] Split examples and snippets (#8944)

This also updates the bazel scripts to behave more like the C++ and Java
examples, and updates the copybara scripts to be able to sync up
`mostrobotpy`
This commit is contained in:
PJ Reiniger
2026-06-03 22:43:16 -04:00
committed by GitHub
parent a734275cc5
commit dca59147e1
134 changed files with 111 additions and 80 deletions

View File

@@ -0,0 +1,37 @@
#
# 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 commands2
import constants
from .drivedistance import DriveDistance
from .releasehatch import ReleaseHatch
from subsystems.drivesubsystem import DriveSubsystem
from subsystems.hatchsubsystem import HatchSubsystem
class ComplexAuto(commands2.SequentialCommandGroup):
"""
A complex auto command that drives forward, releases a hatch, and then drives backward.
"""
def __init__(self, drive: DriveSubsystem, hatch: HatchSubsystem):
super().__init__(
# Drive forward the specified distance
DriveDistance(
constants.kAutoDriveDistanceInches, constants.kAutoDriveVelocity, drive
),
# Release the hatch
ReleaseHatch(hatch),
# Drive backward the specified distance
DriveDistance(
constants.kAutoBackupDistanceInches,
-constants.kAutoDriveVelocity,
drive,
),
)

View File

@@ -0,0 +1,27 @@
#
# 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 typing
import commands2
from subsystems.drivesubsystem import DriveSubsystem
class DefaultDrive(commands2.Command):
def __init__(
self,
drive: DriveSubsystem,
forward: typing.Callable[[], float],
rotation: typing.Callable[[], float],
) -> None:
self.drive = drive
self.forward = forward
self.rotation = rotation
self.addRequirements(self.drive)
def execute(self) -> None:
self.drive.arcadeDrive(self.forward(), self.rotation())

View File

@@ -0,0 +1,30 @@
#
# 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 commands2
from subsystems.drivesubsystem import DriveSubsystem
class DriveDistance(commands2.Command):
def __init__(self, inches: float, velocity: float, drive: DriveSubsystem) -> None:
self.distance = inches
self.velocity = velocity
self.drive = drive
self.addRequirements(drive)
def initialize(self) -> None:
self.drive.resetEncoders()
self.drive.arcadeDrive(self.velocity, 0)
def execute(self) -> None:
self.drive.arcadeDrive(self.velocity, 0)
def end(self, interrupted: bool) -> None:
self.drive.arcadeDrive(0, 0)
def isFinished(self) -> bool:
return abs(self.drive.getAverageEncoderDistance()) >= self.distance

View File

@@ -0,0 +1,20 @@
#
# 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 commands2
from subsystems.hatchsubsystem import HatchSubsystem
class GrabHatch(commands2.Command):
def __init__(self, hatch: HatchSubsystem) -> None:
self.hatch = hatch
self.addRequirements(hatch)
def initialize(self) -> None:
self.hatch.grabHatch()
def isFinished(self) -> bool:
return True

View File

@@ -0,0 +1,20 @@
#
# 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 commands2
from subsystems.drivesubsystem import DriveSubsystem
class HalveDriveVelocity(commands2.Command):
def __init__(self, drive: DriveSubsystem) -> None:
self.drive = drive
def initialize(self) -> None:
self.drive.setMaxOutput(0.5)
def end(self, interrupted: bool) -> None:
self.drive.setMaxOutput(1.0)

View File

@@ -0,0 +1,14 @@
#
# 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 commands2
from subsystems.hatchsubsystem import HatchSubsystem
class ReleaseHatch(commands2.InstantCommand):
def __init__(self, hatch: HatchSubsystem) -> None:
super().__init__(hatch.releaseHatch, hatch)

View File

@@ -0,0 +1,51 @@
#
# 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
# numerical or boolean constants. Don't use this for any other purpose!
#
import math
import wpilib
# Motors
kLeftMotor1Port = 0
kLeftMotor2Port = 1
kRightMotor1Port = 2
kRightMotor2Port = 3
# Encoders
kLeftEncoderPorts = (0, 1)
kRightEncoderPorts = (2, 3)
kLeftEncoderReversed = False
kRightEncoderReversed = True
kEncoderCPR = 1024
kWheelDiameterInches = 6
# Assumes the encoders are directly mounted on the wheel shafts
kEncoderDistancePerPulse = (kWheelDiameterInches * math.pi) / kEncoderCPR
# Hatch
kHatchSolenoidModuleType = wpilib.PneumaticsModuleType.CTRE_PCM
kHatchSolenoidModule = 0
kHatchSolenoidPorts = (0, 1)
# Autonomous
kAutoDriveDistanceInches = 60
kAutoBackupDistanceInches = 20
kAutoDriveVelocity = 0.5
# Operator Interface
kDriverControllerPort = 0
# Physical parameters
kDriveTrainMotorCount = 2
kTrackWidth = 0.381 * 2
kGearingRatio = 8
kWheelRadius = 0.0508
# kEncoderResolution = -

View File

@@ -0,0 +1,71 @@
#!/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 typing
import commands2
import wpilib
from robotcontainer import RobotContainer
class MyRobot(commands2.TimedCommandRobot):
"""
Command v2 robots are encouraged to inherit from TimedCommandRobot, which
has an implementation of robotPeriodic which runs the scheduler for you
"""
autonomousCommand: typing.Optional[commands2.Command] = None
def __init__(self) -> None:
"""
This function is run when the robot is first started up and should be used for any
initialization code.
"""
super().__init__()
# Instantiate our RobotContainer. This will perform all our button bindings, and put our
# autonomous chooser on the dashboard.
self.container = RobotContainer()
# Start recording to data log
wpilib.DataLogManager.start()
# Record DS control and joystick data.
# Change to `false` to not record joystick data.
wpilib.DriverStation.startDataLog(wpilib.DataLogManager.getLog(), True)
def disabledInit(self) -> None:
"""This function is called once each time the robot enters Disabled mode."""
def disabledPeriodic(self) -> None:
"""This function is called periodically when disabled"""
def autonomousInit(self) -> None:
"""This autonomous runs the autonomous command selected by your RobotContainer class."""
self.autonomousCommand = self.container.getAutonomousCommand()
if self.autonomousCommand:
self.autonomousCommand.schedule()
def autonomousPeriodic(self) -> None:
"""This function is called periodically during autonomous"""
def teleopInit(self) -> None:
# This makes sure that the autonomous stops running when
# teleop starts running. If you want the autonomous to
# continue until interrupted by another command, remove
# this line or comment it out.
if self.autonomousCommand:
self.autonomousCommand.cancel()
def teleopPeriodic(self) -> None:
"""This function is called periodically during operator control"""
def utilityInit(self) -> None:
# Cancels all running commands at the start of utility mode
commands2.CommandScheduler.getInstance().cancelAll()

View File

@@ -0,0 +1,93 @@
#
# 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
import commands2
import commands2.button
import constants
from commands.complexauto import ComplexAuto
from commands.drivedistance import DriveDistance
from commands.defaultdrive import DefaultDrive
from commands.grabhatch import GrabHatch
from commands.halvedrivevelocity import HalveDriveVelocity
from commands.releasehatch import ReleaseHatch
from subsystems.drivesubsystem import DriveSubsystem
from subsystems.hatchsubsystem import HatchSubsystem
class RobotContainer:
"""
This class is where the bulk of the robot should be declared. Since Command-based is a
"declarative" paradigm, very little robot logic should actually be handled in the :class:`.Robot`
periodic methods (other than the scheduler calls). Instead, the structure of the robot (including
subsystems, commands, and button mappings) should be declared here.
"""
def __init__(self) -> None:
# The driver's controller
# self.driverController = wpilib.NiDsXboxController(constants.kDriverControllerPort)
self.driverController = wpilib.Joystick(constants.kDriverControllerPort)
# The robot's subsystems
self.drive = DriveSubsystem()
self.hatch = HatchSubsystem()
# Autonomous routines
# A simple auto routine that drives forward a specified distance, and then stops.
self.simpleAuto = DriveDistance(
constants.kAutoDriveDistanceInches, constants.kAutoDriveVelocity, self.drive
)
# A complex auto routine that drives forward, drops a hatch, and then drives backward.
self.complexAuto = ComplexAuto(self.drive, self.hatch)
# Chooser
self.chooser = wpilib.SendableChooser()
# Add commands to the autonomous command chooser
self.chooser.setDefaultOption("Simple Auto", self.simpleAuto)
self.chooser.addOption("Complex Auto", self.complexAuto)
# Put the chooser on the dashboard
wpilib.SmartDashboard.putData("Autonomous", self.chooser)
self.configureButtonBindings()
# set up default drive command
self.drive.setDefaultCommand(
DefaultDrive(
self.drive,
lambda: -self.driverController.getY(),
lambda: self.driverController.getX(),
)
)
def configureButtonBindings(self):
"""
Use this method to define your button->command mappings. Buttons can be created by
instantiating a wpilib.GenericHID or one of its subclasses (Joystick or XboxController),
and then passing it to a JoystickButton.
"""
commands2.button.JoystickButton(self.driverController, 1).onTrue(
GrabHatch(self.hatch)
)
commands2.button.JoystickButton(self.driverController, 2).onTrue(
ReleaseHatch(self.hatch)
)
commands2.button.JoystickButton(self.driverController, 3).whileTrue(
HalveDriveVelocity(self.drive)
)
def getAutonomousCommand(self) -> commands2.Command:
return self.chooser.getSelected()

View File

@@ -0,0 +1,65 @@
#
# 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 commands2
import wpilib
import constants
class DriveSubsystem(commands2.Subsystem):
def __init__(self) -> None:
self.left1 = wpilib.PWMVictorSPX(constants.kLeftMotor1Port)
self.left2 = wpilib.PWMVictorSPX(constants.kLeftMotor2Port)
self.right1 = wpilib.PWMVictorSPX(constants.kRightMotor1Port)
self.right2 = wpilib.PWMVictorSPX(constants.kRightMotor2Port)
# We need to invert one side of the drivetrain so that positive velocities
# result in both sides moving forward. Depending on how your robot's
# drivetrain is constructed, you might have to invert the left side instead.
self.right1.setInverted(True)
# The robot's drive
self.drive = wpilib.DifferentialDrive(self.left1, self.right1)
# The left-side drive encoder
self.leftEncoder = wpilib.Encoder(
*constants.kLeftEncoderPorts,
reverseDirection=constants.kLeftEncoderReversed
)
# The right-side drive encoder
self.rightEncoder = wpilib.Encoder(
*constants.kRightEncoderPorts,
reverseDirection=constants.kRightEncoderReversed
)
# Sets the distance per pulse for the encoders
self.leftEncoder.setDistancePerPulse(constants.kEncoderDistancePerPulse)
self.rightEncoder.setDistancePerPulse(constants.kEncoderDistancePerPulse)
def arcadeDrive(self, fwd: float, rot: float) -> None:
"""
Drives the robot using arcade controls.
:param fwd: the commanded forward movement
:param rot: the commanded rotation
"""
self.drive.arcadeDrive(fwd, rot)
def resetEncoders(self) -> None:
"""Resets the drive encoders to currently read a position of 0."""
def getAverageEncoderDistance(self) -> float:
"""Gets the average distance of the TWO encoders."""
return (self.leftEncoder.getDistance() + self.rightEncoder.getDistance()) / 2.0
def setMaxOutput(self, maxOutput: float):
"""
Sets the max output of the drive. Useful for scaling the
drive to drive more slowly.
"""
self.drive.setMaxOutput(maxOutput)

View File

@@ -0,0 +1,28 @@
#
# 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
import commands2
import constants
class HatchSubsystem(commands2.Subsystem):
def __init__(self) -> None:
self.hatchSolenoid = wpilib.DoubleSolenoid(
constants.kHatchSolenoidModule,
constants.kHatchSolenoidModuleType,
*constants.kHatchSolenoidPorts
)
def grabHatch(self) -> None:
"""Grabs the hatch"""
self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.FORWARD)
def releaseHatch(self) -> None:
"""Releases the hatch"""
self.hatchSolenoid.set(wpilib.DoubleSolenoid.Value.REVERSE)