[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,34 @@
#
# 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.drivetrain import Drivetrain
class ArcadeDrive(commands2.Command):
def __init__(
self,
drive: Drivetrain,
forward: typing.Callable[[], float],
rotation: typing.Callable[[], float],
) -> None:
"""Creates a new ArcadeDrive. This command will drive your robot according to the velocity supplier
lambdas. This command does not terminate.
:param drivetrain: The drivetrain subsystem on which this command will run
:param forward: Callable supplier of forward/backward velocity
:param rotation: Callable supplier of rotational velocity
"""
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,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 commands2
from commands.drivedistance import DriveDistance
from commands.turndegrees import TurnDegrees
from subsystems.drivetrain import Drivetrain
class AutonomousDistance(commands2.SequentialCommandGroup):
def __init__(self, drive: Drivetrain) -> None:
"""Creates a new Autonomous Drive based on distance. This will drive out for a specified distance,
turn around and drive back.
:param drivetrain: The drivetrain subsystem on which this command will run
"""
super().__init__()
self.addCommands(
DriveDistance(-0.5, 10, drive),
TurnDegrees(-0.5, 180, drive),
DriveDistance(-0.5, 10, drive),
TurnDegrees(0.5, 180, drive),
)

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 commands.drivetime import DriveTime
from commands.turntime import TurnTime
from subsystems.drivetrain import Drivetrain
class AutonomousTime(commands2.SequentialCommandGroup):
def __init__(self, drive: Drivetrain) -> None:
"""Creates a new Autonomous Drive based on time. This will drive out for a period of time, turn
around for time (equivalent to time to turn around) and drive forward again. This should mimic
driving out, turning around and driving back.
:param drivetrain: The drive subsystem on which this command will run
"""
super().__init__()
self.addCommands(
DriveTime(-0.6, 2.0, drive),
TurnTime(-0.5, 1.3, drive),
DriveTime(-0.6, 2.0, drive),
TurnTime(0.5, 1.3, drive),
)

View File

@@ -0,0 +1,43 @@
#
# 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.drivetrain import Drivetrain
class DriveDistance(commands2.Command):
def __init__(self, velocity: float, inches: float, drive: Drivetrain) -> None:
"""Creates a new DriveDistance. This command will drive your your robot for a desired distance at
a desired velocity.
:param velocity: The velocity at which the robot will drive
:param inches: The number of inches the robot will drive
:param drive: The drivetrain subsystem on which this command will run
"""
self.distance = inches
self.velocity = velocity
self.drive = drive
self.addRequirements(drive)
def initialize(self) -> None:
"""Called when the command is initially scheduled."""
self.drive.arcadeDrive(0, 0)
self.drive.resetEncoders()
def execute(self) -> None:
"""Called every time the scheduler runs while the command is scheduled."""
self.drive.arcadeDrive(self.velocity, 0)
def end(self, interrupted: bool) -> None:
"""Called once the command ends or is interrupted."""
self.drive.arcadeDrive(0, 0)
def isFinished(self) -> bool:
"""Returns true when the command should end."""
# Compare distance travelled from start to desired distance
return abs(self.drive.getAverageDistanceInch()) >= self.distance

View File

@@ -0,0 +1,46 @@
#
# 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
from subsystems.drivetrain import Drivetrain
class DriveTime(commands2.Command):
"""Creates a new DriveTime. This command will drive your robot for a desired velocity and time."""
def __init__(self, velocity: float, time: float, drive: Drivetrain) -> None:
"""Creates a new DriveTime. This command will drive your robot for a desired velocity and time.
:param velocity: The velocity which the robot will drive. Negative is in reverse.
:param time: How much time to drive in seconds
:param drive: The drivetrain subsystem on which this command will run
"""
self.velocity = velocity
self.duration = time
self.drive = drive
self.addRequirements(drive)
self.startTime = 0.0
def initialize(self) -> None:
"""Called when the command is initially scheduled."""
self.startTime = wpilib.Timer.getTimestamp()
self.drive.arcadeDrive(0, 0)
def execute(self) -> None:
"""Called every time the scheduler runs while the command is scheduled."""
self.drive.arcadeDrive(self.velocity, 0)
def end(self, interrupted: bool) -> None:
"""Called once the command ends or is interrupted."""
self.drive.arcadeDrive(0, 0)
def isFinished(self) -> bool:
"""Returns true when the command should end"""
return wpilib.Timer.getTimestamp() - self.startTime >= self.duration

View File

@@ -0,0 +1,57 @@
#
# 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 math
import commands2
from subsystems.drivetrain import Drivetrain
class TurnDegrees(commands2.Command):
def __init__(self, velocity: float, degrees: float, drive: Drivetrain) -> None:
"""Creates a new TurnDegrees. This command will turn your robot for a desired rotation (in
degrees) and rotational velocity.
:param velocity: The velocity which the robot will drive. Negative is in reverse.
:param degrees: Degrees to turn. Leverages encoders to compare distance.
:param drive: The drive subsystem on which this command will run
"""
self.degrees = degrees
self.velocity = velocity
self.drive = drive
self.addRequirements(drive)
def initialize(self) -> None:
"""Called when the command is initially scheduled."""
# Set motors to stop, read encoder values for starting point
self.drive.arcadeDrive(0, 0)
self.drive.resetEncoders()
def execute(self) -> None:
"""Called every time the scheduler runs while the command is scheduled."""
self.drive.arcadeDrive(0, self.velocity)
def end(self, interrupted: bool) -> None:
"""Called once the command ends or is interrupted."""
self.drive.arcadeDrive(0, 0)
def isFinished(self) -> bool:
"""Returns true when the command should end."""
# Need to convert distance travelled to degrees. The Standard
# Romi Chassis found here, https://www.pololu.com/category/203/romi-chassis-kits,
# has a wheel placement diameter (149 mm) - width of the wheel (8 mm) = 141 mm
# or 5.551 inches. We then take into consideration the width of the tires.
inchPerDegree = math.pi * 5.551 / 360.0
# Compare distance travelled from start to distance based on degree turn
return self._getAverageTurningDistance() >= inchPerDegree * self.degrees
def _getAverageTurningDistance(self) -> float:
leftDistance = abs(self.drive.getLeftDistanceInch())
rightDistance = abs(self.drive.getRightDistanceInch())
return (leftDistance + rightDistance) / 2.0

View File

@@ -0,0 +1,48 @@
#
# 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
from subsystems.drivetrain import Drivetrain
class TurnTime(commands2.Command):
"""Creates a new TurnTime command. This command will turn your robot for a
desired rotational velocity and time.
"""
def __init__(self, velocity: float, time: float, drive: Drivetrain) -> None:
"""Creates a new TurnTime.
:param velocity: The velocity which the robot will turn. Negative is in reverse.
:param time: How much time to turn in seconds
:param drive: The drive subsystem on which this command will run
"""
self.rotationalVelocity = velocity
self.duration = time
self.drive = drive
self.addRequirements(drive)
self.startTime = 0.0
def initialize(self) -> None:
"""Called when the command is initially scheduled."""
self.startTime = wpilib.Timer.getTimestamp()
self.drive.arcadeDrive(0, 0)
def execute(self) -> None:
"""Called every time the scheduler runs while the command is scheduled."""
self.drive.arcadeDrive(0, self.rotationalVelocity)
def end(self, interrupted: bool) -> None:
"""Called once the command ends or is interrupted."""
self.drive.arcadeDrive(0, 0)
def isFinished(self) -> bool:
"""Returns true when the command should end"""
return wpilib.Timer.getTimestamp() - self.startTime >= self.duration