Skip to content

Commit d687d7f

Browse files
committed
Update examples for 2027
- Most of this was done with Codex so there may be some errors, but I manually reviewed all of it
1 parent 9d825f9 commit d687d7f

101 files changed

Lines changed: 1375 additions & 1342 deletions

File tree

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

examples/robot/AddressableLED/robot.py

Lines changed: 25 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -6,49 +6,40 @@
66
#
77

88
import wpilib
9-
10-
kLEDBuffer = 60
9+
import wpimath.units
1110

1211

1312
class MyRobot(wpilib.TimedRobot):
14-
def robotInit(self):
15-
# PWM Port 9
16-
# Must be a PWM header, not MXP or DIO
17-
self.led = wpilib.AddressableLED(9)
18-
19-
# LED Data
20-
self.ledData = [wpilib.AddressableLED.LEDData() for _ in range(kLEDBuffer)]
13+
def __init__(self) -> None:
14+
super().__init__()
2115

22-
# Store what the last hue of the first pixel is
23-
self.rainbowFirstPixelHue = 0
16+
# SmartIO port 1
17+
self.led = wpilib.AddressableLED(1)
2418

25-
# Default to a length of 60, start empty output
26-
# Length is expensive to set, so only set it once, then just update data
27-
self.led.setLength(kLEDBuffer)
19+
# Reuse buffer
20+
# Default to a length of 60
21+
self.ledData = [wpilib.AddressableLED.LEDData() for _ in range(60)]
22+
self.led.setLength(len(self.ledData))
2823

2924
# Set the data
3025
self.led.setData(self.ledData)
31-
self.led.start()
32-
33-
def robotPeriodic(self):
34-
# Fill the buffer with a rainbow
35-
self.rainbow()
36-
37-
# Set the LEDs
38-
self.led.setData(self.ledData)
3926

40-
def rainbow(self):
41-
# For every pixel
42-
for i in range(kLEDBuffer):
43-
# Calculate the hue - hue is easier for rainbows because the color
44-
# shape is a circle so only one value needs to precess
45-
hue = (self.rainbowFirstPixelHue + (i * 180 / kLEDBuffer)) % 180
27+
# Create an LED pattern that will display a rainbow across
28+
# all hues at maximum saturation and half brightness
29+
self.rainbow = wpilib.LEDPattern.rainbow(255, 128)
4630

47-
# Set the value
48-
self.ledData[i].setHSV(int(hue), 255, 128)
31+
# Our LED strip has a density of 120 LEDs per meter
32+
self.kLedSpacing = 1 / 120.0
4933

50-
# Increase by to make the rainbow "move"
51-
self.rainbowFirstPixelHue += 3
34+
# Create a new pattern that scrolls the rainbow pattern across the LED strip, moving at a
35+
# speed of 1 meter per second.
36+
self.scrollingRainbow = self.rainbow.scrollAtAbsoluteSpeed(
37+
1,
38+
self.kLedSpacing,
39+
)
5240

53-
# Check bounds
54-
self.rainbowFirstPixelHue %= 180
41+
def robotPeriodic(self) -> None:
42+
# Update the buffer with the rainbow animation
43+
self.scrollingRainbow.applyTo(self.ledData)
44+
# Set the LEDs
45+
self.led.setData(self.ledData)

examples/robot/AprilTagsVision/robot.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14,9 +14,11 @@ class MyRobot(wpilib.TimedRobot):
1414
"""
1515
This is a demo program showing the detection of AprilTags. The image is acquired from the USB
1616
camera, then any detected AprilTags are marked up on the image and sent to the dashboard.
17-
Be aware that the performance on this is much worse than a coprocessor solution!"""
17+
Be aware that the performance on this is much worse than a coprocessor solution!
18+
"""
1819

19-
def robotInit(self):
20+
def __init__(self):
21+
super().__init__()
2022
# Your image processing code will be launched via a stub that will set up logging and initialize NetworkTables
2123
# to talk to your robot code.
2224
# https://robotpy.readthedocs.io/en/stable/vision/roborio.html#important-notes

examples/robot/AprilTagsVision/vision.py

Lines changed: 89 additions & 76 deletions
Original file line numberDiff line numberDiff line change
@@ -23,8 +23,10 @@
2323
def main():
2424
detector = robotpy_apriltag.AprilTagDetector()
2525

26-
# Look for tag36h11, correct 3 error bits
27-
detector.addFamily("tag36h11", 3)
26+
# look for tag36h11, correct 1 error bit (hamming distance 1)
27+
# hamming 1 allocates 781KB, 2 allocates 27.4 MB, 3 allocates 932 MB
28+
# max of 1 recommended for RoboRIO 1, while hamming 2 is feasible on the RoboRIO 2
29+
detector.addFamily("tag36h11", 1)
2830

2931
# Set up Pose Estimator - parameters are for a Microsoft Lifecam HD-3000
3032
# (https://www.chiefdelphi.com/t/wpilib-apriltagdetector-sample-code/421411/21)
@@ -54,85 +56,96 @@ def main():
5456
grayMat = np.zeros(shape=(480, 640), dtype=np.uint8)
5557

5658
# Instantiate once
57-
tags = [] # The list where the tags will be stored
58-
outlineColor = (0, 255, 0) # Color of Tag Outline
59-
crossColor = (0, 0, 25) # Color of Cross
59+
tags = []
60+
outlineColor = (0, 255, 0)
61+
crossColor = (0, 0, 255)
6062

6163
# Output the list to Network Tables
6264
tagsTable = ntcore.NetworkTableInstance.getDefault().getTable("apriltags")
6365
pubTags = tagsTable.getIntegerArrayTopic("tags").publish()
6466

65-
while True:
66-
# Tell the CvSink to grab a frame from the camera and put it
67-
# in the source mat. If there is an error notify the output.
68-
if cvSink.grabFrame(mat) == 0:
69-
# Send the output frame the error
70-
outputStream.notifyError(cvSink.getError())
71-
72-
# Skip the rest of the current iteration
73-
continue
74-
75-
cv2.cvtColor(mat, cv2.COLOR_RGB2GRAY, dst=grayMat)
76-
77-
detections = detector.detect(grayMat)
78-
79-
tags.clear()
80-
81-
for detection in detections:
82-
# Remember the tag we saw
83-
tags.append(detection.getId())
84-
85-
# Draw lines around the tag
86-
for i in range(4):
87-
j = (i + 1) % 4
88-
point1 = (int(detection.getCorner(i).x), int(detection.getCorner(i).y))
89-
point2 = (int(detection.getCorner(j).x), int(detection.getCorner(j).y))
90-
mat = cv2.line(mat, point1, point2, outlineColor, 2)
91-
92-
# Mark the center of the tag
93-
cx = int(detection.getCenter().x)
94-
cy = int(detection.getCenter().y)
95-
ll = 10
96-
mat = cv2.line(
97-
mat,
98-
(cx - ll, cy),
99-
(cx + ll, cy),
100-
crossColor,
101-
2,
102-
)
103-
mat = cv2.line(
104-
mat,
105-
(cx, cy - ll),
106-
(cx, cy + ll),
107-
crossColor,
108-
2,
109-
)
110-
111-
# Identify the tag
112-
mat = cv2.putText(
113-
mat,
114-
str(detection.getId()),
115-
(cx + ll, cy),
116-
cv2.FONT_HERSHEY_SIMPLEX,
117-
1,
118-
crossColor,
119-
3,
120-
)
121-
122-
# Determine Tag Pose
123-
pose = estimator.estimate(detection)
124-
125-
# put pose into dashboard
126-
rot = pose.rotation()
127-
tagsTable.getEntry(f"pose_{detection.getId()}").setDoubleArray(
128-
[pose.X(), pose.Y(), pose.Z(), rot.X(), rot.Y(), rot.Z()]
129-
)
130-
131-
# Put List of Tags onto Dashboard
132-
pubTags.set(tags)
133-
134-
# Give output stream a new image to display
135-
outputStream.putFrame(mat)
67+
try:
68+
while True:
69+
# Tell the CvSink to grab a frame from the camera and put it
70+
# in the source mat. If there is an error notify the output.
71+
if cvSink.grabFrame(mat) == 0:
72+
# Send the output frame the error
73+
outputStream.notifyError(cvSink.getError())
74+
75+
# Skip the rest of the current iteration
76+
continue
77+
78+
cv2.cvtColor(mat, cv2.COLOR_RGB2GRAY, dst=grayMat)
79+
80+
detections = detector.detect(grayMat)
81+
82+
# have not seen any tags yet
83+
tags.clear()
84+
85+
for detection in detections:
86+
# remember we saw this tag
87+
tags.append(detection.getId())
88+
89+
# draw lines around the tag
90+
for i in range(4):
91+
j = (i + 1) % 4
92+
point1 = (
93+
int(detection.getCorner(i).x),
94+
int(detection.getCorner(i).y),
95+
)
96+
point2 = (
97+
int(detection.getCorner(j).x),
98+
int(detection.getCorner(j).y),
99+
)
100+
mat = cv2.line(mat, point1, point2, outlineColor, 2)
101+
102+
# mark the center of the tag
103+
cx = int(detection.getCenter().x)
104+
cy = int(detection.getCenter().y)
105+
ll = 10
106+
mat = cv2.line(
107+
mat,
108+
(cx - ll, cy),
109+
(cx + ll, cy),
110+
crossColor,
111+
2,
112+
)
113+
mat = cv2.line(
114+
mat,
115+
(cx, cy - ll),
116+
(cx, cy + ll),
117+
crossColor,
118+
2,
119+
)
120+
121+
# identify the tag
122+
mat = cv2.putText(
123+
mat,
124+
str(detection.getId()),
125+
(cx + ll, cy),
126+
cv2.FONT_HERSHEY_SIMPLEX,
127+
1,
128+
crossColor,
129+
3,
130+
)
131+
132+
# determine pose
133+
pose = estimator.estimate(detection)
134+
135+
# put pose into dashboard
136+
rot = pose.rotation()
137+
tagsTable.getEntry(f"pose_{detection.getId()}").setDoubleArray(
138+
[pose.X(), pose.Y(), pose.Z(), rot.X(), rot.Y(), rot.Z()]
139+
)
140+
141+
# put list of tags onto dashboard
142+
pubTags.set(tags)
143+
144+
# Give output stream a new image to display
145+
outputStream.putFrame(mat)
146+
finally:
147+
pubTags.close()
148+
detector.close()
136149

137150
# The camera code will be killed when the robot.py program exits. If you wish to perform cleanup,
138151
# you should register an atexit handler. The child process will NOT be launched when running the robot code in

examples/robot/ArcadeDrive/robot.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,6 @@
66
#
77

88
import wpilib
9-
import wpilib.drive
109

1110

1211
class MyRobot(wpilib.TimedRobot):
@@ -15,12 +14,13 @@ class MyRobot(wpilib.TimedRobot):
1514
Runs the motors with arcade steering.
1615
"""
1716

18-
def robotInit(self):
17+
def __init__(self):
1918
"""Robot initialization function"""
19+
super().__init__()
2020

2121
leftMotor = wpilib.PWMSparkMax(0)
2222
rightMotor = wpilib.PWMSparkMax(1)
23-
self.robotDrive = wpilib.drive.DifferentialDrive(leftMotor, rightMotor)
23+
self.robotDrive = wpilib.DifferentialDrive(leftMotor, rightMotor)
2424
self.stick = wpilib.Joystick(0)
2525

2626
# We need to invert one side of the drivetrain so that positive voltages
@@ -32,4 +32,4 @@ def teleopPeriodic(self):
3232
# Drive with arcade drive.
3333
# That means that the Y axis drives forward
3434
# and backward, and the X turns left and right.
35-
self.robotDrive.arcadeDrive(self.stick.getY(), self.stick.getX())
35+
self.robotDrive.arcadeDrive(-self.stick.getY(), -self.stick.getX())

examples/robot/ArcadeDriveXboxController/robot.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,6 @@
66
#
77

88
import wpilib
9-
import wpilib.drive
109

1110

1211
class MyRobot(wpilib.TimedRobot):
@@ -15,12 +14,13 @@ class MyRobot(wpilib.TimedRobot):
1514
Runs the motors with split arcade steering and an Xbox controller.
1615
"""
1716

18-
def robotInit(self):
17+
def __init__(self):
1918
"""Robot initialization function"""
19+
super().__init__()
2020

2121
leftMotor = wpilib.PWMSparkMax(0)
2222
rightMotor = wpilib.PWMSparkMax(1)
23-
self.robotDrive = wpilib.drive.DifferentialDrive(leftMotor, rightMotor)
23+
self.robotDrive = wpilib.DifferentialDrive(leftMotor, rightMotor)
2424
self.driverController = wpilib.XboxController(0)
2525

2626
# We need to invert one side of the drivetrain so that positive voltages

0 commit comments

Comments
 (0)