Skip to content

Commit 72c0b82

Browse files
committed
Add XrpReference example
- Tests don't pass because static variables
1 parent 4e7b525 commit 72c0b82

File tree

12 files changed

+653
-0
lines changed

12 files changed

+653
-0
lines changed

XrpReference/commands/arcadedrive.py

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,35 @@
1+
#
2+
# Copyright (c) FIRST and other WPILib contributors.
3+
# Open Source Software; you can modify and/or share it under the terms of
4+
# the WPILib BSD license file in the root directory of this project.
5+
#
6+
7+
import typing
8+
import commands2
9+
from subsystems.drivetrain import Drivetrain
10+
11+
12+
class ArcadeDrive(commands2.Command):
13+
def __init__(
14+
self,
15+
drive: Drivetrain,
16+
xaxisSpeedSupplier: typing.Callable[[], float],
17+
zaxisRotateSupplier: typing.Callable[[], float],
18+
) -> None:
19+
"""Creates a new ArcadeDrive. This command will drive your robot according to the speed supplier
20+
lambdas. This command does not terminate.
21+
22+
:param drivetrain: The drivetrain subsystem on which this command will run
23+
:param xaxisSpeedSupplier: Callable supplier of forward/backward speed
24+
:param zaxisRotateSupplier: Callable supplier of rotational speed
25+
"""
26+
super().__init__()
27+
28+
self.drive = drive
29+
self.xaxisSpeedSupplier = xaxisSpeedSupplier
30+
self.zaxisRotateSupplier = zaxisRotateSupplier
31+
32+
self.addRequirements(self.drive)
33+
34+
def execute(self) -> None:
35+
self.drive.arcadeDrive(self.xaxisSpeedSupplier(), self.zaxisRotateSupplier())
Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
1+
#
2+
# Copyright (c) FIRST and other WPILib contributors.
3+
# Open Source Software; you can modify and/or share it under the terms of
4+
# the WPILib BSD license file in the root directory of this project.
5+
#
6+
7+
import commands2
8+
9+
from commands.drivedistance import DriveDistance
10+
from commands.turndegrees import TurnDegrees
11+
from subsystems.drivetrain import Drivetrain
12+
13+
14+
class AutonomousDistance(commands2.SequentialCommandGroup):
15+
def __init__(self, drive: Drivetrain) -> None:
16+
"""Creates a new Autonomous Drive based on distance. This will drive out for a specified distance,
17+
turn around and drive back.
18+
19+
:param drivetrain: The drivetrain subsystem on which this command will run
20+
"""
21+
super().__init__()
22+
23+
self.addCommands(
24+
DriveDistance(-0.5, 10, drive),
25+
TurnDegrees(-0.5, 180, drive),
26+
DriveDistance(-0.5, 10, drive),
27+
TurnDegrees(0.5, 180, drive),
28+
)
Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
#
2+
# Copyright (c) FIRST and other WPILib contributors.
3+
# Open Source Software; you can modify and/or share it under the terms of
4+
# the WPILib BSD license file in the root directory of this project.
5+
#
6+
7+
import commands2
8+
9+
from commands.drivetime import DriveTime
10+
from commands.turntime import TurnTime
11+
from subsystems.drivetrain import Drivetrain
12+
13+
14+
class AutonomousTime(commands2.SequentialCommandGroup):
15+
def __init__(self, drive: Drivetrain) -> None:
16+
"""Creates a new Autonomous Drive based on time. This will drive out for a period of time, turn
17+
around for time (equivalent to time to turn around) and drive forward again. This should mimic
18+
driving out, turning around and driving back.
19+
20+
:param drivetrain: The drive subsystem on which this command will run
21+
22+
"""
23+
super().__init__()
24+
25+
self.addCommands(
26+
DriveTime(-0.6, 2.0, drive),
27+
TurnTime(-0.5, 1.3, drive),
28+
DriveTime(-0.6, 2.0, drive),
29+
TurnTime(0.5, 1.3, drive),
30+
)
Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
#
2+
# Copyright (c) FIRST and other WPILib contributors.
3+
# Open Source Software; you can modify and/or share it under the terms of
4+
# the WPILib BSD license file in the root directory of this project.
5+
#
6+
7+
import commands2
8+
9+
from subsystems.drivetrain import Drivetrain
10+
11+
12+
class DriveDistance(commands2.Command):
13+
def __init__(self, speed: float, inches: float, drive: Drivetrain) -> None:
14+
"""Creates a new DriveDistance. This command will drive your your robot for a desired distance at
15+
a desired speed.
16+
17+
:param speed: The speed at which the robot will drive
18+
:param inches: The number of inches the robot will drive
19+
:param drive: The drivetrain subsystem on which this command will run
20+
"""
21+
super().__init__()
22+
23+
self.distance = inches
24+
self.speed = speed
25+
self.drive = drive
26+
self.addRequirements(drive)
27+
28+
def initialize(self) -> None:
29+
"""Called when the command is initially scheduled."""
30+
self.drive.arcadeDrive(0, 0)
31+
self.drive.resetEncoders()
32+
33+
def execute(self) -> None:
34+
"""Called every time the scheduler runs while the command is scheduled."""
35+
self.drive.arcadeDrive(self.speed, 0)
36+
37+
def end(self, interrupted: bool) -> None:
38+
"""Called once the command ends or is interrupted."""
39+
self.drive.arcadeDrive(0, 0)
40+
41+
def isFinished(self) -> bool:
42+
"""Returns true when the command should end."""
43+
# Compare distance travelled from start to desired distance
44+
return abs(self.drive.getAverageDistanceInch()) >= self.distance

XrpReference/commands/drivetime.py

Lines changed: 47 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,47 @@
1+
#
2+
# Copyright (c) FIRST and other WPILib contributors.
3+
# Open Source Software; you can modify and/or share it under the terms of
4+
# the WPILib BSD license file in the root directory of this project.
5+
#
6+
7+
import commands2
8+
import wpilib
9+
10+
from subsystems.drivetrain import Drivetrain
11+
12+
13+
class DriveTime(commands2.Command):
14+
"""Creates a new DriveTime. This command will drive your robot for a desired speed and time."""
15+
16+
def __init__(self, speed: float, time: float, drive: Drivetrain) -> None:
17+
"""Creates a new DriveTime. This command will drive your robot for a desired speed and time.
18+
19+
:param speed: The speed which the robot will drive. Negative is in reverse.
20+
:param time: How much time to drive in seconds
21+
:param drive: The drivetrain subsystem on which this command will run
22+
"""
23+
super().__init__()
24+
25+
self.speed = speed
26+
self.duration = time
27+
self.drive = drive
28+
self.addRequirements(drive)
29+
30+
self.startTime = 0.0
31+
32+
def initialize(self) -> None:
33+
"""Called when the command is initially scheduled."""
34+
self.startTime = wpilib.Timer.getFPGATimestamp()
35+
self.drive.arcadeDrive(0, 0)
36+
37+
def execute(self) -> None:
38+
"""Called every time the scheduler runs while the command is scheduled."""
39+
self.drive.arcadeDrive(self.speed, 0)
40+
41+
def end(self, interrupted: bool) -> None:
42+
"""Called once the command ends or is interrupted."""
43+
self.drive.arcadeDrive(0, 0)
44+
45+
def isFinished(self) -> bool:
46+
"""Returns true when the command should end"""
47+
return wpilib.Timer.getFPGATimestamp() - self.startTime >= self.duration

XrpReference/commands/turndegrees.py

Lines changed: 58 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
#
2+
# Copyright (c) FIRST and other WPILib contributors.
3+
# Open Source Software; you can modify and/or share it under the terms of
4+
# the WPILib BSD license file in the root directory of this project.
5+
#
6+
7+
import math
8+
import commands2
9+
10+
from subsystems.drivetrain import Drivetrain
11+
12+
13+
class TurnDegrees(commands2.Command):
14+
def __init__(self, speed: float, degrees: float, drive: Drivetrain) -> None:
15+
"""Creates a new TurnDegrees. This command will turn your robot for a desired rotation (in
16+
degrees) and rotational speed.
17+
18+
:param speed: The speed which the robot will drive. Negative is in reverse.
19+
:param degrees: Degrees to turn. Leverages encoders to compare distance.
20+
:param drive: The drive subsystem on which this command will run
21+
"""
22+
super().__init__()
23+
24+
self.degrees = degrees
25+
self.speed = speed
26+
self.drive = drive
27+
self.addRequirements(drive)
28+
29+
def initialize(self) -> None:
30+
"""Called when the command is initially scheduled."""
31+
# Set motors to stop, read encoder values for starting point
32+
self.drive.arcadeDrive(0, 0)
33+
self.drive.resetEncoders()
34+
35+
def execute(self) -> None:
36+
"""Called every time the scheduler runs while the command is scheduled."""
37+
self.drive.arcadeDrive(0, self.speed)
38+
39+
def end(self, interrupted: bool) -> None:
40+
"""Called once the command ends or is interrupted."""
41+
self.drive.arcadeDrive(0, 0)
42+
43+
def isFinished(self) -> bool:
44+
"""Returns true when the command should end."""
45+
46+
# Need to convert distance travelled to degrees. The Standard
47+
# XRP Chassis found here, https://www.sparkfun.com/products/22230,
48+
# has a wheel placement diameter (163 mm) - width of the wheel (8 mm) = 155 mm
49+
# or 6.102 inches. We then take into consideration the width of the tires.
50+
inchPerDegree = math.pi * 6.102 / 360
51+
52+
# Compare distance travelled from start to distance based on degree turn
53+
return self._getAverageTurningDistance() >= inchPerDegree * self.degrees
54+
55+
def _getAverageTurningDistance(self) -> float:
56+
leftDistance = abs(self.drive.getLeftDistanceInch())
57+
rightDistance = abs(self.drive.getRightDistanceInch())
58+
return (leftDistance + rightDistance) / 2.0

XrpReference/commands/turntime.py

Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
1+
#
2+
# Copyright (c) FIRST and other WPILib contributors.
3+
# Open Source Software; you can modify and/or share it under the terms of
4+
# the WPILib BSD license file in the root directory of this project.
5+
#
6+
7+
import commands2
8+
import wpilib
9+
10+
from subsystems.drivetrain import Drivetrain
11+
12+
13+
class TurnTime(commands2.Command):
14+
"""Creates a new TurnTime command. This command will turn your robot for a
15+
desired rotational speed and time.
16+
"""
17+
18+
def __init__(self, speed: float, time: float, drive: Drivetrain) -> None:
19+
"""Creates a new TurnTime.
20+
21+
:param speed: The speed which the robot will turn. Negative is in reverse.
22+
:param time: How much time to turn in seconds
23+
:param drive: The drive subsystem on which this command will run
24+
"""
25+
super().__init__()
26+
27+
self.rotationalSpeed = speed
28+
self.duration = time
29+
self.drive = drive
30+
self.addRequirements(drive)
31+
32+
self.startTime = 0.0
33+
34+
def initialize(self) -> None:
35+
"""Called when the command is initially scheduled."""
36+
self.startTime = wpilib.Timer.getFPGATimestamp()
37+
self.drive.arcadeDrive(0, 0)
38+
39+
def execute(self) -> None:
40+
"""Called every time the scheduler runs while the command is scheduled."""
41+
self.drive.arcadeDrive(0, self.rotationalSpeed)
42+
43+
def end(self, interrupted: bool) -> None:
44+
"""Called once the command ends or is interrupted."""
45+
self.drive.arcadeDrive(0, 0)
46+
47+
def isFinished(self) -> bool:
48+
"""Returns true when the command should end"""
49+
return wpilib.Timer.getFPGATimestamp() - self.startTime >= self.duration

XrpReference/robot.py

Lines changed: 97 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,97 @@
1+
#!/usr/bin/env python3
2+
#
3+
# Copyright (c) FIRST and other WPILib contributors.
4+
# Open Source Software; you can modify and/or share it under the terms of
5+
# the WPILib BSD license file in the root directory of this project.
6+
#
7+
8+
#
9+
# Example that shows how to connect to a XRP from RobotPy
10+
#
11+
# Requirements
12+
# ------------
13+
#
14+
# You must have the robotpy-xrp package installed. This is best done via:
15+
#
16+
# # Windows
17+
# py -3 -m pip install robotpy[commands2,sim,xrp]
18+
#
19+
# # Linux/macOS
20+
# pip3 install robotpy[commands2,sim,xrp]
21+
#
22+
# Run the program
23+
# ---------------
24+
#
25+
# To run the program you will need to explicitly use the XRP option:
26+
#
27+
# # Windows
28+
# py -3 robotpy sim --xrp
29+
#
30+
# # Linux/macOS
31+
# python robotpy sim --xrp
32+
#
33+
# By default the WPILib simulation GUI will be displayed. To disable the display
34+
# you can add the --nogui option
35+
#
36+
37+
import os
38+
import typing
39+
40+
import wpilib
41+
import commands2
42+
43+
from robotcontainer import RobotContainer
44+
45+
# If your XRP isn't at the default address, set that here
46+
os.environ["HALSIMXRP_HOST"] = "192.168.42.1"
47+
os.environ["HALSIMXRP_PORT"] = "3540"
48+
49+
50+
class MyRobot(commands2.TimedCommandRobot):
51+
"""
52+
Command v2 robots are encouraged to inherit from TimedCommandRobot, which
53+
has an implementation of robotPeriodic which runs the scheduler for you
54+
"""
55+
56+
autonomousCommand: typing.Optional[commands2.Command] = None
57+
58+
def robotInit(self) -> None:
59+
"""
60+
This function is run when the robot is first started up and should be used for any
61+
initialization code.
62+
"""
63+
64+
# Instantiate our RobotContainer. This will perform all our button bindings, and put our
65+
# autonomous chooser on the dashboard.
66+
self.container = RobotContainer()
67+
68+
def disabledInit(self) -> None:
69+
"""This function is called once each time the robot enters Disabled mode."""
70+
71+
def disabledPeriodic(self) -> None:
72+
"""This function is called periodically when disabled"""
73+
74+
def autonomousInit(self) -> None:
75+
"""This autonomous runs the autonomous command selected by your RobotContainer class."""
76+
self.autonomousCommand = self.container.getAutonomousCommand()
77+
78+
if self.autonomousCommand:
79+
self.autonomousCommand.schedule()
80+
81+
def autonomousPeriodic(self) -> None:
82+
"""This function is called periodically during autonomous"""
83+
84+
def teleopInit(self) -> None:
85+
# This makes sure that the autonomous stops running when
86+
# teleop starts running. If you want the autonomous to
87+
# continue until interrupted by another command, remove
88+
# this line or comment it out.
89+
if self.autonomousCommand:
90+
self.autonomousCommand.cancel()
91+
92+
def teleopPeriodic(self) -> None:
93+
"""This function is called periodically during operator control"""
94+
95+
def testInit(self) -> None:
96+
# Cancels all running commands at the start of test mode
97+
commands2.CommandScheduler.getInstance().cancelAll()

0 commit comments

Comments
 (0)