mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[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:
45
robotpyExamples/snippets/AddressableLED/robot.py
Normal file
45
robotpyExamples/snippets/AddressableLED/robot.py
Normal file
@@ -0,0 +1,45 @@
|
||||
#!/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 wpilib
|
||||
import wpimath.units
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
def __init__(self) -> None:
|
||||
super().__init__()
|
||||
|
||||
# SmartIO port 1
|
||||
self.led = wpilib.AddressableLED(1)
|
||||
|
||||
# Reuse buffer
|
||||
# Default to a length of 60
|
||||
self.ledData = [wpilib.AddressableLED.LEDData() for _ in range(60)]
|
||||
self.led.setLength(len(self.ledData))
|
||||
|
||||
# Set the data
|
||||
self.led.setData(self.ledData)
|
||||
|
||||
# Create an LED pattern that will display a rainbow across
|
||||
# all hues at maximum saturation and half brightness
|
||||
self.rainbow = wpilib.LEDPattern.rainbow(255, 128)
|
||||
|
||||
# Our LED strip has a density of 120 LEDs per meter
|
||||
self.kLedSpacing = 1 / 120.0
|
||||
|
||||
# Create a new pattern that scrolls the rainbow pattern across the LED strip, moving at a
|
||||
# velocity of 1 meter per second.
|
||||
self.scrollingRainbow = self.rainbow.scrollAtAbsoluteVelocity(
|
||||
1,
|
||||
self.kLedSpacing,
|
||||
)
|
||||
|
||||
def robotPeriodic(self) -> None:
|
||||
# Update the buffer with the rainbow animation
|
||||
self.scrollingRainbow.applyTo(self.ledData)
|
||||
# Set the LEDs
|
||||
self.led.setData(self.ledData)
|
||||
26
robotpyExamples/snippets/AprilTagsVision/robot.py
Normal file
26
robotpyExamples/snippets/AprilTagsVision/robot.py
Normal file
@@ -0,0 +1,26 @@
|
||||
#!/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 wpilib
|
||||
import wpilib.cameraserver
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
"""
|
||||
This is a demo program showing the detection of AprilTags. The image is acquired from the USB
|
||||
camera, then any detected AprilTags are marked up on the image and sent to the dashboard.
|
||||
Be aware that the performance on this is much worse than a coprocessor solution!
|
||||
"""
|
||||
|
||||
def __init__(self):
|
||||
super().__init__()
|
||||
# Your image processing code will be launched via a stub that will set up logging and initialize NetworkTables
|
||||
# to talk to your robot code.
|
||||
# https://robotpy.readthedocs.io/en/stable/vision/roborio.html#important-notes
|
||||
|
||||
wpilib.CameraServer.launch("vision.py:main")
|
||||
151
robotpyExamples/snippets/AprilTagsVision/vision.py
Normal file
151
robotpyExamples/snippets/AprilTagsVision/vision.py
Normal file
@@ -0,0 +1,151 @@
|
||||
#
|
||||
# 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 ntcore
|
||||
import robotpy_apriltag
|
||||
from cscore import CameraServer
|
||||
|
||||
import cv2
|
||||
import numpy as np
|
||||
|
||||
#
|
||||
# This code will work both on a RoboRIO and on other platforms. The exact mechanism
|
||||
# to run it differs depending on whether you’re on a RoboRIO or a coprocessor
|
||||
#
|
||||
# https://robotpy.readthedocs.io/en/stable/vision/code.html
|
||||
|
||||
|
||||
def main():
|
||||
detector = robotpy_apriltag.AprilTagDetector()
|
||||
|
||||
# look for tag36h11, correct 1 error bit (hamming distance 1)
|
||||
# hamming 1 allocates 781KB, 2 allocates 27.4 MB, 3 allocates 932 MB
|
||||
# max of 1 recommended for RoboRIO 1, while hamming 2 is feasible on the RoboRIO 2
|
||||
detector.addFamily("tag36h11", 1)
|
||||
|
||||
# Set up Pose Estimator - parameters are for a Microsoft Lifecam HD-3000
|
||||
# (https://www.chiefdelphi.com/t/wpilib-apriltagdetector-sample-code/421411/21)
|
||||
poseEstConfig = robotpy_apriltag.AprilTagPoseEstimator.Config(
|
||||
0.1651,
|
||||
699.3778103158814,
|
||||
677.7161226393544,
|
||||
345.6059345433618,
|
||||
207.12741326228522,
|
||||
)
|
||||
estimator = robotpy_apriltag.AprilTagPoseEstimator(poseEstConfig)
|
||||
|
||||
# Get the UsbCamera from CameraServer
|
||||
camera = CameraServer.startAutomaticCapture()
|
||||
|
||||
# Set the resolution
|
||||
camera.setResolution(640, 480)
|
||||
|
||||
# Get a CvSink. This will capture Mats from the camera
|
||||
cvSink = CameraServer.getVideo()
|
||||
|
||||
# Set up a CvSource. This will send images back to the Dashboard
|
||||
outputStream = CameraServer.putVideo("Detected", 640, 480)
|
||||
|
||||
# Mats are very memory expensive. Let's reuse these.
|
||||
mat = np.zeros((480, 640, 3), dtype=np.uint8)
|
||||
grayMat = np.zeros(shape=(480, 640), dtype=np.uint8)
|
||||
|
||||
# Instantiate once
|
||||
tags = []
|
||||
outlineColor = (0, 255, 0)
|
||||
crossColor = (0, 0, 255)
|
||||
|
||||
# Output the list to Network Tables
|
||||
tagsTable = ntcore.NetworkTableInstance.getDefault().getTable("apriltags")
|
||||
pubTags = tagsTable.getIntegerArrayTopic("tags").publish()
|
||||
|
||||
try:
|
||||
while True:
|
||||
# Tell the CvSink to grab a frame from the camera and put it
|
||||
# in the source mat. If there is an error notify the output.
|
||||
if cvSink.grabFrame(mat) == 0:
|
||||
# Send the output frame the error
|
||||
outputStream.notifyError(cvSink.getError())
|
||||
|
||||
# Skip the rest of the current iteration
|
||||
continue
|
||||
|
||||
cv2.cvtColor(mat, cv2.COLOR_RGB2GRAY, dst=grayMat)
|
||||
|
||||
detections = detector.detect(grayMat)
|
||||
|
||||
# have not seen any tags yet
|
||||
tags.clear()
|
||||
|
||||
for detection in detections:
|
||||
# remember we saw this tag
|
||||
tags.append(detection.getId())
|
||||
|
||||
# draw lines around the tag
|
||||
for i in range(4):
|
||||
j = (i + 1) % 4
|
||||
point1 = (
|
||||
int(detection.getCorner(i).x),
|
||||
int(detection.getCorner(i).y),
|
||||
)
|
||||
point2 = (
|
||||
int(detection.getCorner(j).x),
|
||||
int(detection.getCorner(j).y),
|
||||
)
|
||||
mat = cv2.line(mat, point1, point2, outlineColor, 2)
|
||||
|
||||
# mark the center of the tag
|
||||
cx = int(detection.getCenter().x)
|
||||
cy = int(detection.getCenter().y)
|
||||
ll = 10
|
||||
mat = cv2.line(
|
||||
mat,
|
||||
(cx - ll, cy),
|
||||
(cx + ll, cy),
|
||||
crossColor,
|
||||
2,
|
||||
)
|
||||
mat = cv2.line(
|
||||
mat,
|
||||
(cx, cy - ll),
|
||||
(cx, cy + ll),
|
||||
crossColor,
|
||||
2,
|
||||
)
|
||||
|
||||
# identify the tag
|
||||
mat = cv2.putText(
|
||||
mat,
|
||||
str(detection.getId()),
|
||||
(cx + ll, cy),
|
||||
cv2.FONT_HERSHEY_SIMPLEX,
|
||||
1,
|
||||
crossColor,
|
||||
3,
|
||||
)
|
||||
|
||||
# determine pose
|
||||
pose = estimator.estimate(detection)
|
||||
|
||||
# put pose into dashboard
|
||||
rot = pose.rotation()
|
||||
tagsTable.getEntry(f"pose_{detection.getId()}").setDoubleArray(
|
||||
[pose.X(), pose.Y(), pose.Z(), rot.X(), rot.Y(), rot.Z()]
|
||||
)
|
||||
|
||||
# put list of tags onto dashboard
|
||||
pubTags.set(tags)
|
||||
|
||||
# Give output stream a new image to display
|
||||
outputStream.putFrame(mat)
|
||||
finally:
|
||||
pubTags.close()
|
||||
detector.close()
|
||||
|
||||
# The camera code will be killed when the robot.py program exits. If you wish to perform cleanup,
|
||||
# you should register an atexit handler. The child process will NOT be launched when running the robot code in
|
||||
# simulation or unit testing mode
|
||||
56
robotpyExamples/snippets/CANPDP/robot.py
Executable file
56
robotpyExamples/snippets/CANPDP/robot.py
Executable file
@@ -0,0 +1,56 @@
|
||||
#!/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 wpilib
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
"""
|
||||
This is a sample program showing how to retrieve information from the Power
|
||||
Distribution Panel via CAN. The information will be displayed under variables
|
||||
through the SmartDashboard.
|
||||
"""
|
||||
|
||||
def __init__(self):
|
||||
"""Robot initialization function"""
|
||||
super().__init__()
|
||||
|
||||
# Object for dealing with the Power Distribution Panel (PDP).
|
||||
self.pdp = wpilib.PowerDistribution(0)
|
||||
|
||||
# Put the PDP itself to the dashboard
|
||||
wpilib.SmartDashboard.putData("PDP", self.pdp)
|
||||
|
||||
def robotPeriodic(self):
|
||||
# Get the current going through channel 7, in Amperes.
|
||||
# The PDP returns the current in increments of 0.125A.
|
||||
# At low currents the current readings tend to be less accurate.
|
||||
current7 = self.pdp.getCurrent(7)
|
||||
wpilib.SmartDashboard.putNumber("Current Channel 7", current7)
|
||||
|
||||
# Get the voltage going into the PDP, in Volts.
|
||||
# The PDP returns the voltage in increments of 0.05 Volts.
|
||||
voltage = self.pdp.getVoltage()
|
||||
wpilib.SmartDashboard.putNumber("Voltage", voltage)
|
||||
|
||||
# Retrieves the temperature of the PDP, in degrees Celsius.
|
||||
temperatureCelsius = self.pdp.getTemperature()
|
||||
wpilib.SmartDashboard.putNumber("Temperature", temperatureCelsius)
|
||||
|
||||
# Get the total current of all channels.
|
||||
totalCurrent = self.pdp.getTotalCurrent()
|
||||
wpilib.SmartDashboard.putNumber("Total Current", totalCurrent)
|
||||
|
||||
# Get the total power of all channels.
|
||||
# Power is the bus voltage multiplied by the current with the units Watts.
|
||||
totalPower = self.pdp.getTotalPower()
|
||||
wpilib.SmartDashboard.putNumber("Total Power", totalPower)
|
||||
|
||||
# Get the total energy of all channels.
|
||||
# Energy is the power summed over time with units Joules.
|
||||
totalEnergy = self.pdp.getTotalEnergy()
|
||||
wpilib.SmartDashboard.putNumber("Total Energy", totalEnergy)
|
||||
49
robotpyExamples/snippets/DigitalCommunication/robot.py
Executable file
49
robotpyExamples/snippets/DigitalCommunication/robot.py
Executable file
@@ -0,0 +1,49 @@
|
||||
#!/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 wpilib
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
"""
|
||||
This is a sample program demonstrating how to communicate to a light controller from the robot
|
||||
code using the roboRIO's DIO ports.
|
||||
"""
|
||||
|
||||
# define ports for digitalcommunication with light controller
|
||||
kAlliancePort = 0
|
||||
kEnabledPort = 1
|
||||
kAutonomousPort = 2
|
||||
kAlertPort = 3
|
||||
|
||||
def __init__(self):
|
||||
"""Robot initialization function"""
|
||||
super().__init__()
|
||||
|
||||
self.allianceOutput = wpilib.DigitalOutput(self.kAlliancePort)
|
||||
self.enabledOutput = wpilib.DigitalOutput(self.kEnabledPort)
|
||||
self.autonomousOutput = wpilib.DigitalOutput(self.kAutonomousPort)
|
||||
self.alertOutput = wpilib.DigitalOutput(self.kAlertPort)
|
||||
|
||||
def robotPeriodic(self):
|
||||
setAlliance = False
|
||||
alliance = wpilib.MatchState.getAlliance()
|
||||
if alliance:
|
||||
setAlliance = alliance == wpilib.Alliance.RED
|
||||
|
||||
# pull alliance port high if on red alliance, pull low if on blue alliance
|
||||
self.allianceOutput.set(setAlliance)
|
||||
|
||||
# pull enabled port high if enabled, low if disabled
|
||||
self.enabledOutput.set(wpilib.RobotState.isEnabled())
|
||||
|
||||
# pull auto port high if in autonomous, low if in teleop (or disabled)
|
||||
self.autonomousOutput.set(wpilib.RobotState.isAutonomous())
|
||||
|
||||
# pull alert port high if match time remaining is between 30 and 25 seconds
|
||||
matchTime = wpilib.MatchState.getMatchTime()
|
||||
self.alertOutput.set(30 >= matchTime >= 25)
|
||||
27
robotpyExamples/snippets/DutyCycleInput/robot.py
Executable file
27
robotpyExamples/snippets/DutyCycleInput/robot.py
Executable file
@@ -0,0 +1,27 @@
|
||||
#!/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 wpilib
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
def __init__(self):
|
||||
"""Robot initialization function"""
|
||||
super().__init__()
|
||||
|
||||
self.dutyCycle = wpilib.DutyCycle(0)
|
||||
|
||||
def robotPeriodic(self):
|
||||
# Duty Cycle Frequency in Hz
|
||||
frequency = self.dutyCycle.getFrequency()
|
||||
|
||||
# Output of duty cycle, ranging from 0 to 1
|
||||
# 1 is fully on, 0 is fully off
|
||||
output = self.dutyCycle.getOutput()
|
||||
|
||||
wpilib.SmartDashboard.putNumber("Frequency", frequency)
|
||||
wpilib.SmartDashboard.putNumber("Duty Cycle", output)
|
||||
87
robotpyExamples/snippets/EventLoop/robot.py
Normal file
87
robotpyExamples/snippets/EventLoop/robot.py
Normal file
@@ -0,0 +1,87 @@
|
||||
#!/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 wpilib
|
||||
import wpimath
|
||||
|
||||
SHOT_VELOCITY = 200.0 # rpm
|
||||
TOLERANCE = 8.0 # rpm
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
def __init__(self) -> None:
|
||||
super().__init__()
|
||||
|
||||
self.shooter = wpilib.PWMSparkMax(0)
|
||||
self.shooterEncoder = wpilib.Encoder(0, 1)
|
||||
self.controller = wpimath.PIDController(0.3, 0, 0)
|
||||
self.feedforward = wpimath.SimpleMotorFeedforwardMeters(0.1, 0.065)
|
||||
|
||||
self.kicker = wpilib.PWMSparkMax(1)
|
||||
|
||||
self.intake = wpilib.PWMSparkMax(2)
|
||||
|
||||
self.loop = wpilib.EventLoop()
|
||||
self.joystick = wpilib.Joystick(0)
|
||||
|
||||
# Called once at the beginning of the robot program.
|
||||
self.controller.setTolerance(TOLERANCE)
|
||||
|
||||
isBallAtKickerEvent = wpilib.BooleanEvent(
|
||||
self.loop, lambda: False
|
||||
) # self.kickerSensor.getRange() < KICKER_THRESHOLD
|
||||
intakeButton = wpilib.BooleanEvent(
|
||||
self.loop, lambda: self.joystick.getRawButton(2)
|
||||
)
|
||||
|
||||
# if the thumb button is held
|
||||
intakeButton.and_(isBallAtKickerEvent.negate()).ifHigh(
|
||||
# and there is not a ball at the kicker
|
||||
# activate the intake
|
||||
lambda: self.intake.set(0.5)
|
||||
)
|
||||
|
||||
# if the thumb button is not held
|
||||
intakeButton.negate().or_(isBallAtKickerEvent).ifHigh(
|
||||
# or there is a ball in the kicker
|
||||
# stop the intake
|
||||
self.intake.stopMotor
|
||||
)
|
||||
|
||||
shootTrigger = wpilib.BooleanEvent(self.loop, self.joystick.getTrigger)
|
||||
|
||||
# if the trigger is held
|
||||
shootTrigger.ifHigh(
|
||||
# accelerate the shooter wheel
|
||||
lambda: self.shooter.setVoltage(
|
||||
self.controller.calculate(self.shooterEncoder.getRate(), SHOT_VELOCITY)
|
||||
+ self.feedforward.calculate(SHOT_VELOCITY)
|
||||
)
|
||||
)
|
||||
|
||||
# if not, stop
|
||||
shootTrigger.negate().ifHigh(self.shooter.stopMotor)
|
||||
|
||||
atTargetVelocity = wpilib.BooleanEvent(
|
||||
self.loop, self.controller.atSetpoint
|
||||
).debounce(
|
||||
# debounce for more stability
|
||||
0.2
|
||||
)
|
||||
|
||||
# if we're at the target velocity, kick the ball into the shooter wheel
|
||||
atTargetVelocity.ifHigh(lambda: self.kicker.set(0.7))
|
||||
|
||||
# when we stop being at the target velocity, it means the ball was shot
|
||||
atTargetVelocity.falling().ifHigh(
|
||||
# so stop the kicker
|
||||
self.kicker.stopMotor
|
||||
)
|
||||
|
||||
def robotPeriodic(self) -> None:
|
||||
# poll all the bindings
|
||||
self.loop.poll()
|
||||
108
robotpyExamples/snippets/FlywheelBangBangController/robot.py
Executable file
108
robotpyExamples/snippets/FlywheelBangBangController/robot.py
Executable file
@@ -0,0 +1,108 @@
|
||||
#!/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 wpilib
|
||||
import math
|
||||
|
||||
import wpilib.simulation
|
||||
import wpimath
|
||||
import wpimath.units
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
"""
|
||||
This is a sample program to demonstrate the use of a BangBangController with a flywheel to
|
||||
control RPM.
|
||||
"""
|
||||
|
||||
kMotorPort = 0
|
||||
kEncoderAChannel = 0
|
||||
kEncoderBChannel = 1
|
||||
|
||||
# Max setpoint for joystick control in RPM
|
||||
kMaxSetpointValue = 6000.0
|
||||
|
||||
# Gains are for example purposes only - must be determined for your own robot!
|
||||
kFlywheelKs = 0.0001 # V
|
||||
kFlywheelKv = 0.000195 # V/RPM
|
||||
kFlywheelKa = 0.0003 # V/(RPM/s)
|
||||
|
||||
# Reduction between motors and encoder, as output over input. If the flywheel
|
||||
# spins slower than the motors, this number should be greater than one.
|
||||
kFlywheelGearing = 1.0
|
||||
|
||||
# 1/2 MR²
|
||||
kFlywheelMomentOfInertia = (
|
||||
0.5
|
||||
* wpimath.units.lbsToKilograms(1.5)
|
||||
* math.pow(wpimath.units.inchesToMeters(4), 2)
|
||||
)
|
||||
|
||||
def __init__(self) -> None:
|
||||
"""Robot initialization function"""
|
||||
super().__init__()
|
||||
|
||||
self.flywheelMotor = wpilib.PWMSparkMax(self.kMotorPort)
|
||||
self.encoder = wpilib.Encoder(self.kEncoderAChannel, self.kEncoderBChannel)
|
||||
|
||||
self.bangBangControler = wpimath.BangBangController()
|
||||
|
||||
# Gains are for example purposes only - must be determined for your own robot!
|
||||
self.feedforward = wpimath.SimpleMotorFeedforwardMeters(
|
||||
self.kFlywheelKs, self.kFlywheelKv, self.kFlywheelKa
|
||||
)
|
||||
|
||||
# Joystick to control setpoint
|
||||
self.joystick = wpilib.Joystick(0)
|
||||
|
||||
# Simulation classes help us simulate our robot
|
||||
|
||||
self.gearbox = wpimath.DCMotor.NEO(1)
|
||||
|
||||
self.plant = wpimath.Models.flywheelFromPhysicalConstants(
|
||||
self.gearbox, self.kFlywheelGearing, self.kFlywheelMomentOfInertia
|
||||
)
|
||||
|
||||
self.flywheelSim = wpilib.simulation.FlywheelSim(self.plant, self.gearbox)
|
||||
self.encoderSim = wpilib.simulation.EncoderSim(self.encoder)
|
||||
|
||||
# Add bang-bang controller to SmartDashboard and networktables.
|
||||
wpilib.SmartDashboard.putData(self.bangBangControler)
|
||||
|
||||
def teleopPeriodic(self) -> None:
|
||||
"""Controls flywheel to a set velocity (RPM) controlled by a joystick."""
|
||||
|
||||
# Scale setpoint value between 0 and maxSetpointValue
|
||||
setpoint = max(
|
||||
0.0,
|
||||
self.joystick.getRawAxis(0)
|
||||
* wpimath.units.rotationsPerMinuteToRadiansPerSecond(
|
||||
self.kMaxSetpointValue
|
||||
),
|
||||
)
|
||||
|
||||
# Set setpoint and measurement of the bang-bang controller
|
||||
bangOutput = (
|
||||
self.bangBangControler.calculate(self.encoder.getRate(), setpoint) * 12.0
|
||||
)
|
||||
|
||||
# Controls a motor with the output of the BangBang controller and a
|
||||
# feedforward. The feedforward is reduced slightly to avoid overvelocitying
|
||||
# the shooter.
|
||||
self.flywheelMotor.setVoltage(
|
||||
bangOutput + 0.9 * self.feedforward.calculate(setpoint)
|
||||
)
|
||||
|
||||
def simulationPeriodic(self) -> None:
|
||||
"""Update our simulation. This should be run every robot loop in simulation."""
|
||||
# To update our simulation, we set motor voltage inputs, update the
|
||||
# simulation, and write the simulated velocities to our simulated encoder
|
||||
self.flywheelSim.setInputVoltage(
|
||||
self.flywheelMotor.getThrottle() * wpilib.RobotController.getInputVoltage()
|
||||
)
|
||||
self.flywheelSim.update(0.02)
|
||||
self.encoderSim.setRate(self.flywheelSim.getAngularVelocity())
|
||||
20
robotpyExamples/snippets/HttpCamera/robot.py
Normal file
20
robotpyExamples/snippets/HttpCamera/robot.py
Normal file
@@ -0,0 +1,20 @@
|
||||
#!/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 wpilib
|
||||
import wpilib.cameraserver
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
def __init__(self):
|
||||
super().__init__()
|
||||
# Your image processing code will be launched via a stub that will set up logging and initialize NetworkTables
|
||||
# to talk to your robot code.
|
||||
# https://robotpy.readthedocs.io/en/stable/vision/roborio.html#important-notes
|
||||
|
||||
wpilib.CameraServer.launch("vision.py:main")
|
||||
71
robotpyExamples/snippets/HttpCamera/vision.py
Normal file
71
robotpyExamples/snippets/HttpCamera/vision.py
Normal file
@@ -0,0 +1,71 @@
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
|
||||
"""
|
||||
This is a demo program showing the use of OpenCV to do vision processing. The image is acquired
|
||||
from an HTTP camera, then a rectangle is put on the image and sent to the dashboard. OpenCV has
|
||||
many methods for different types of processing.
|
||||
"""
|
||||
|
||||
import numpy
|
||||
import cscore
|
||||
from cscore import CameraServer
|
||||
import cv2
|
||||
|
||||
#
|
||||
# This code will work both on a RoboRIO and on other platforms. The exact mechanism
|
||||
# to run it differs depending on whether you’re on a RoboRIO or a coprocessor
|
||||
#
|
||||
# https://robotpy.readthedocs.io/en/stable/vision/code.html
|
||||
|
||||
|
||||
def main():
|
||||
# Create an HTTP camera. The address will need to be modified to have the
|
||||
# correct team number. The exact path will depend on the source.
|
||||
camera = cscore.HttpCamera("HTTP Camera", "http://10.x.y.11/video/stream.mjpg")
|
||||
# Start capturing images
|
||||
CameraServer.startAutomaticCapture(camera)
|
||||
# Set the resolution
|
||||
camera.setResolution(640, 480)
|
||||
|
||||
# Get a CvSink. This will capture Mats from the camera
|
||||
cvSink = CameraServer.getVideo()
|
||||
|
||||
# Setup a CvSource. This will send images back to the Dashboard
|
||||
outputStream = CameraServer.putVideo("Rectangle", 640, 480)
|
||||
|
||||
# Mats are very memory expensive. Lets reuse this Mat.
|
||||
mat = numpy.zeros((480, 640, 3), dtype="uint8")
|
||||
|
||||
# Declare the color of the rectangle
|
||||
rectColor = (255, 255, 255)
|
||||
|
||||
# The camera code will be killed when the robot.py program exits. If you wish to perform cleanup,
|
||||
# you should register an atexit handler. The child process will NOT be launched when running the robot code in
|
||||
# simulation or unit testing mode
|
||||
|
||||
while True:
|
||||
# Tell the CvSink to grab a frame from the camera and put it in the source mat. If there is an error notify the
|
||||
# output.
|
||||
|
||||
if cvSink.grabFrame(mat) == 0:
|
||||
# Send the output the error.
|
||||
outputStream.notifyError(cvSink.getError())
|
||||
|
||||
# skip the rest of the current iteration
|
||||
continue
|
||||
|
||||
# Put a rectangle on the image
|
||||
mat = cv2.rectangle(
|
||||
img=mat,
|
||||
pt1=(100, 100),
|
||||
pt2=(400, 400),
|
||||
color=rectColor,
|
||||
lineType=5,
|
||||
)
|
||||
|
||||
# Give the output stream a new image to display
|
||||
outputStream.putFrame(mat)
|
||||
54
robotpyExamples/snippets/I2CCommunication/robot.py
Executable file
54
robotpyExamples/snippets/I2CCommunication/robot.py
Executable file
@@ -0,0 +1,54 @@
|
||||
#!/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 wpilib
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
"""
|
||||
This is a sample program demonstrating how to communicate to a light controller from the robot
|
||||
code using the roboRIO's I2C port.
|
||||
"""
|
||||
|
||||
PORT = wpilib.I2C.Port.PORT_0
|
||||
DEVICE_ADDRESS = 4
|
||||
|
||||
def __init__(self):
|
||||
"""Robot initialization function"""
|
||||
super().__init__()
|
||||
|
||||
self.arduino = wpilib.I2C(self.PORT, self.DEVICE_ADDRESS)
|
||||
|
||||
def writeString(self, s: str):
|
||||
# Creates a char array from the input string
|
||||
chars = s.encode("ascii")
|
||||
|
||||
# Writes bytes over I2C
|
||||
self.arduino.writeBulk(chars)
|
||||
|
||||
def robotPeriodic(self):
|
||||
# Creates a string to hold current robot state information, including
|
||||
# alliance, enabled state, operation mode, and match time. The message
|
||||
# is sent in format "AEM###" where A is the alliance color, (R)ed or
|
||||
# (B)lue, E is the enabled state, (E)nabled or (D)isabled, M is the
|
||||
# operation mode, (A)utonomous or (T)eleop, and ### is the zero-padded
|
||||
# time remaining in the match.
|
||||
#
|
||||
# For example, "RET043" would indicate that the robot is on the red
|
||||
# alliance, enabled in teleop mode, with 43 seconds left in the match.
|
||||
allianceString = "U"
|
||||
alliance = wpilib.MatchState.getAlliance()
|
||||
if alliance is not None:
|
||||
allianceString = "R" if alliance == wpilib.Alliance.RED else "B"
|
||||
|
||||
enabledString = "E" if wpilib.RobotState.isEnabled() else "D"
|
||||
autoString = "A" if wpilib.RobotState.isAutonomous() else "T"
|
||||
matchTime = wpilib.MatchState.getMatchTime()
|
||||
|
||||
stateMessage = f"{allianceString}{enabledString}{autoString}{matchTime:03f}"
|
||||
|
||||
self.writeString(stateMessage)
|
||||
20
robotpyExamples/snippets/IntermediateVision/robot.py
Executable file
20
robotpyExamples/snippets/IntermediateVision/robot.py
Executable file
@@ -0,0 +1,20 @@
|
||||
#!/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 wpilib
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
"""
|
||||
This is a demo program showing the use of OpenCV to do vision processing. The image is acquired
|
||||
from the USB camera, then a rectangle is put on the image and sent to the dashboard. OpenCV has
|
||||
many methods for different types of processing.
|
||||
"""
|
||||
|
||||
def __init__(self):
|
||||
super().__init__()
|
||||
wpilib.CameraServer.launch("vision.py:main")
|
||||
53
robotpyExamples/snippets/IntermediateVision/vision.py
Normal file
53
robotpyExamples/snippets/IntermediateVision/vision.py
Normal file
@@ -0,0 +1,53 @@
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
|
||||
#
|
||||
# This is a demo program showing the use of OpenCV to do vision processing. The image is acquired
|
||||
# from the USB camera, then a rectangle is put on the image and sent to the dashboard. OpenCV has
|
||||
# many methods for different types of processing.
|
||||
#
|
||||
# NOTE: This code runs in its own process, so we cannot access the robot here,
|
||||
# nor can we create/use/see wpilib objects
|
||||
#
|
||||
# To try this code out locally (if you have robotpy-cscore installed), you
|
||||
# can execute `python3 -m cscore vision.py:main`
|
||||
#
|
||||
|
||||
import cv2
|
||||
import numpy as np
|
||||
|
||||
from cscore import CameraServer as CS
|
||||
|
||||
|
||||
def main():
|
||||
# Get the UsbCamera from CameraServer
|
||||
camera = CS.startAutomaticCapture()
|
||||
# Set the resolution
|
||||
camera.setResolution(640, 480)
|
||||
|
||||
# Get a CvSink. This will capture images from the camera
|
||||
cvSink = CS.getVideo()
|
||||
# Setup a CvSource. This will send images back to the Dashboard
|
||||
outputStream = CS.putVideo("Rectangle", 640, 480)
|
||||
|
||||
# Mats are very memory expensive. Lets reuse this Mat.
|
||||
mat = np.zeros(shape=(480, 640, 3), dtype=np.uint8)
|
||||
|
||||
while True:
|
||||
# Tell the CvSink to grab a frame from the camera and put it
|
||||
# in the source image. If there is an error notify the output.
|
||||
time, mat = cvSink.grabFrame(mat)
|
||||
if time == 0:
|
||||
# Send the output the error.
|
||||
outputStream.notifyError(cvSink.getError())
|
||||
# skip the rest of the current iteration
|
||||
continue
|
||||
|
||||
# Put a rectangle on the image
|
||||
cv2.rectangle(mat, (100, 100), (400, 400), (255, 255, 255), 5)
|
||||
|
||||
# Give the output stream a new image to display
|
||||
outputStream.putFrame(mat)
|
||||
59
robotpyExamples/snippets/MotorControl/robot.py
Executable file
59
robotpyExamples/snippets/MotorControl/robot.py
Executable file
@@ -0,0 +1,59 @@
|
||||
#!/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 wpilib
|
||||
|
||||
import math
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
"""
|
||||
This sample program shows how to control a motor using a joystick. In the operator control part
|
||||
of the program, the joystick is read and the value is written to the motor.
|
||||
|
||||
Joystick analog values range from -1 to 1 and motor controller inputs also range from -1 to 1
|
||||
making it easy to work together.
|
||||
|
||||
In addition, the encoder value of an encoder connected to ports 0 and 1 is consistently sent
|
||||
to the Dashboard.
|
||||
|
||||
Finally, short code snippets show how to invert the motor direction and how to use the motor
|
||||
safety for frc-docs.
|
||||
https://docs.wpilib.org/en/stable/docs/software/hardware-apis/motors/wpi-drive-classes.html
|
||||
"""
|
||||
|
||||
kMotorPort = 0
|
||||
kJoystickPort = 0
|
||||
kEncoderPortA = 0
|
||||
kEncoderPortB = 1
|
||||
|
||||
def __init__(self):
|
||||
"""Robot initialization function"""
|
||||
super().__init__()
|
||||
|
||||
self.motor = wpilib.PWMSparkMax(self.kMotorPort)
|
||||
self.joystick = wpilib.Joystick(self.kJoystickPort)
|
||||
self.encoder = wpilib.Encoder(self.kEncoderPortA, self.kEncoderPortB)
|
||||
# Use SetDistancePerPulse to set the multiplier for GetDistance
|
||||
# This is set up assuming a 6 inch wheel with a 360 CPR encoder.
|
||||
self.encoder.setDistancePerPulse((math.pi * 6) / 360.0)
|
||||
|
||||
# show motor inversion
|
||||
self.motor.setInverted(True)
|
||||
|
||||
# show motor safety features
|
||||
self.motor.setSafetyEnabled(True)
|
||||
self.motor.setSafetyEnabled(False)
|
||||
self.motor.setExpiration(0.1)
|
||||
self.motor.feed()
|
||||
|
||||
def robotPeriodic(self):
|
||||
"""The RobotPeriodic function is called every control packet no matter the robot mode."""
|
||||
wpilib.SmartDashboard.putNumber("Encoder", self.encoder.getDistance())
|
||||
|
||||
def teleopPeriodic(self):
|
||||
self.motor.setThrottle(self.joystick.getY())
|
||||
21
robotpyExamples/snippets/QuickVision/robot.py
Normal file
21
robotpyExamples/snippets/QuickVision/robot.py
Normal file
@@ -0,0 +1,21 @@
|
||||
#!/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 wpilib
|
||||
from wpilib.cameraserver import CameraServer
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
"""
|
||||
Uses the CameraServer class to automatically capture video from a USB webcam and send it to the
|
||||
dashboard without doing any vision processing. This is the easiest way to get camera images
|
||||
to the dashboard. Just add this to the robotInit() method in your program.
|
||||
"""
|
||||
|
||||
def __init__(self):
|
||||
super().__init__()
|
||||
CameraServer().launch()
|
||||
10
robotpyExamples/snippets/SelectCommand/constants.py
Normal file
10
robotpyExamples/snippets/SelectCommand/constants.py
Normal file
@@ -0,0 +1,10 @@
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
|
||||
|
||||
class OIConstants:
|
||||
# Example: the port of the driver's controller
|
||||
kDriverControllerPort = 0
|
||||
67
robotpyExamples/snippets/SelectCommand/robot.py
Normal file
67
robotpyExamples/snippets/SelectCommand/robot.py
Normal file
@@ -0,0 +1,67 @@
|
||||
#!/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 wpilib
|
||||
import commands2
|
||||
import typing
|
||||
|
||||
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()
|
||||
|
||||
def disabledInit(self) -> None:
|
||||
"""This function is called once each time the robot enters Disabled mode."""
|
||||
pass
|
||||
|
||||
def disabledPeriodic(self) -> None:
|
||||
"""This function is called periodically when disabled"""
|
||||
pass
|
||||
|
||||
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"""
|
||||
pass
|
||||
|
||||
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"""
|
||||
pass
|
||||
|
||||
def utilityInit(self) -> None:
|
||||
# Cancels all running commands at the start of utility mode
|
||||
commands2.CommandScheduler.getInstance().cancelAll()
|
||||
67
robotpyExamples/snippets/SelectCommand/robotcontainer.py
Normal file
67
robotpyExamples/snippets/SelectCommand/robotcontainer.py
Normal file
@@ -0,0 +1,67 @@
|
||||
#
|
||||
# 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 enum
|
||||
import commands2
|
||||
|
||||
|
||||
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.
|
||||
"""
|
||||
|
||||
# The enum used as keys for selecting the command to run.
|
||||
class CommandSelector(enum.Enum):
|
||||
ONE = enum.auto()
|
||||
TWO = enum.auto()
|
||||
THREE = enum.auto()
|
||||
|
||||
# An example selector method for the selectcommand.
|
||||
def select(self) -> CommandSelector:
|
||||
"""Returns the selector that will select which command to run.
|
||||
Can base this choice on logical conditions evaluated at runtime.
|
||||
"""
|
||||
return self.CommandSelector.ONE
|
||||
|
||||
def __init__(self) -> None:
|
||||
# An example selectcommand. Will select from the three commands based on the value returned
|
||||
# by the selector method at runtime. Note that selectcommand takes a generic type, so the
|
||||
# selector does not have to be an enum; it could be any desired type (string, integer,
|
||||
# boolean, double...)
|
||||
self.example_select_command = commands2.SelectCommand(
|
||||
# Maps selector values to commands
|
||||
{
|
||||
self.CommandSelector.ONE: commands2.PrintCommand(
|
||||
"Command one was selected!"
|
||||
),
|
||||
self.CommandSelector.TWO: commands2.PrintCommand(
|
||||
"Command two was selected!"
|
||||
),
|
||||
self.CommandSelector.THREE: commands2.PrintCommand(
|
||||
"Command three was selected!"
|
||||
),
|
||||
},
|
||||
self.select,
|
||||
)
|
||||
|
||||
# Configure the button bindings
|
||||
self.configureButtonBindings()
|
||||
|
||||
def configureButtonBindings(self) -> None:
|
||||
"""Use this method to define your button->command mappings. Buttons can be created by
|
||||
instantiating a {GenericHID} or one of its subclasses
|
||||
({org.wpilib.driverstation.Joystick} or {XboxController}), and then calling passing it to a
|
||||
{org.wpilib.command2.button.JoystickButton}.
|
||||
"""
|
||||
|
||||
def getAutonomousCommand(self) -> commands2.Command:
|
||||
"""Use this to pass the autonomous command to the main {Robot} class.
|
||||
|
||||
:returns: the command to run in autonomous
|
||||
"""
|
||||
return self.example_select_command
|
||||
122
robotpyExamples/snippets/Solenoid/robot.py
Normal file
122
robotpyExamples/snippets/Solenoid/robot.py
Normal file
@@ -0,0 +1,122 @@
|
||||
#!/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 wpilib
|
||||
|
||||
kSolenoidButton = 1
|
||||
kDoubleSolenoidForwardButton = 2
|
||||
kDoubleSolenoidReverseButton = 3
|
||||
kCompressorButton = 4
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
"""
|
||||
This is a sample program showing the use of the solenoid classes during operator control. Three
|
||||
buttons from a joystick will be used to control two solenoids: One button to control the position
|
||||
of a single solenoid and the other two buttons to control a double solenoid. Single solenoids can
|
||||
either be on or off, such that the air diverted through them goes through either one channel or
|
||||
the other. Double solenoids have three states: Off, Forward, and Reverse. Forward and Reverse
|
||||
divert the air through the two channels and correspond to the on and off of a single solenoid,
|
||||
but a double solenoid can also be "off", where the solenoid will remain in its default power off
|
||||
state. Additionally, double solenoids take up two channels on your PCM whereas single solenoids
|
||||
only take a single channel.
|
||||
"""
|
||||
|
||||
def __init__(self) -> None:
|
||||
super().__init__()
|
||||
self.joystick = wpilib.Joystick(0)
|
||||
|
||||
# Solenoid corresponds to a single solenoid.
|
||||
# In this case, it's connected to channel 0 of a PH with the default CAN ID.
|
||||
self.solenoid = wpilib.Solenoid(
|
||||
busId=0, moduleType=wpilib.PneumaticsModuleType.REV_PH, channel=0
|
||||
)
|
||||
|
||||
# DoubleSolenoid corresponds to a double solenoid.
|
||||
# In this case, it's connected to channels 1 and 2 of a PH with the default CAN ID.
|
||||
self.doubleSolenoid = wpilib.DoubleSolenoid(
|
||||
busId=0,
|
||||
moduleType=wpilib.PneumaticsModuleType.REV_PH,
|
||||
forwardChannel=1,
|
||||
reverseChannel=2,
|
||||
)
|
||||
|
||||
# Compressor connected to a PH with a default CAN ID (1)
|
||||
self.compressor = wpilib.Compressor(
|
||||
busId=0, moduleType=wpilib.PneumaticsModuleType.REV_PH
|
||||
)
|
||||
|
||||
# Publish elements to dashboard.
|
||||
wpilib.SmartDashboard.putData("Single Solenoid", self.solenoid)
|
||||
wpilib.SmartDashboard.putData("Double Solenoid", self.doubleSolenoid)
|
||||
wpilib.SmartDashboard.putData("Compressor", self.compressor)
|
||||
|
||||
def teleopPeriodic(self) -> None:
|
||||
# Publish some raw data
|
||||
# Get the pressure (in PSI) from the analog sensor connected to the PH.
|
||||
# This function is supported only on the PH!
|
||||
# On a PCM, this function will return 0.
|
||||
wpilib.SmartDashboard.putNumber(
|
||||
"PH Pressure [PSI]", self.compressor.getPressure()
|
||||
)
|
||||
# Get compressor current draw.
|
||||
wpilib.SmartDashboard.putNumber(
|
||||
"Compressor Current", self.compressor.getCurrent()
|
||||
)
|
||||
# Get whether the compressor is active.
|
||||
wpilib.SmartDashboard.putBoolean(
|
||||
"Compressor Active", self.compressor.isEnabled()
|
||||
)
|
||||
# Get the digital pressure switch connected to the PCM/PH.
|
||||
# The switch is open when the pressure is over ~120 PSI.
|
||||
wpilib.SmartDashboard.putBoolean(
|
||||
"Pressure Switch", self.compressor.getPressureSwitchValue()
|
||||
)
|
||||
|
||||
# The output of GetRawButton is true/false depending on whether
|
||||
# the button is pressed; Set takes a boolean for whether
|
||||
# to retract the solenoid (false) or extend it (true).
|
||||
self.solenoid.set(self.joystick.getRawButton(kSolenoidButton))
|
||||
|
||||
# GetRawButtonPressed will only return true once per press.
|
||||
# If a button is pressed, set the solenoid to the respective channel.
|
||||
|
||||
if self.joystick.getRawButtonPressed(kDoubleSolenoidForwardButton):
|
||||
self.doubleSolenoid.set(wpilib.DoubleSolenoid.Value.FORWARD)
|
||||
elif self.joystick.getRawButtonPressed(kDoubleSolenoidReverseButton):
|
||||
self.doubleSolenoid.set(wpilib.DoubleSolenoid.Value.REVERSE)
|
||||
|
||||
# On button press, toggle the compressor.
|
||||
if self.joystick.getRawButtonPressed(kCompressorButton):
|
||||
# Check whether the compressor is currently enabled.
|
||||
isCompressorEnabled = self.compressor.isEnabled()
|
||||
if isCompressorEnabled:
|
||||
# Disable closed-loop mode on the compressor
|
||||
self.compressor.disable()
|
||||
else:
|
||||
# Change the if statements to select the closed-loop you want to use:
|
||||
|
||||
if False:
|
||||
# Enable closed-loop mode based on the digital pressure switch connected to the PCM/PH.
|
||||
# The switch is open when the pressure is over ~120 PSI.
|
||||
self.compressor.enableDigital()
|
||||
|
||||
if True:
|
||||
# Enable closed-loop mode based on the analog pressure sensor connected to the PH.
|
||||
# The compressor will run while the pressure reported by the sensor is in the
|
||||
# specified range ([70 PSI, 120 PSI] in this example).
|
||||
# Analog mode exists only on the PH! On the PCM, this enables digital control.
|
||||
self.compressor.enableAnalog(70, 120)
|
||||
|
||||
if False:
|
||||
# Enable closed-loop mode based on both the digital pressure switch AND the analog
|
||||
# pressure sensor connected to the PH.
|
||||
# The compressor will run while the pressure reported by the analog sensor is in the
|
||||
# specified range ([70 PSI, 120 PSI] in this example) AND the digital switch reports
|
||||
# that the system is not full.
|
||||
# Hybrid mode exists only on the PH! On the PCM, this enables digital control.
|
||||
self.compressor.enableHybrid(70, 120)
|
||||
20
robotpyExamples/snippets/snippets.toml
Normal file
20
robotpyExamples/snippets/snippets.toml
Normal file
@@ -0,0 +1,20 @@
|
||||
[tests]
|
||||
base = [
|
||||
"AddressableLED",
|
||||
"AprilTagsVision",
|
||||
"CANPDP",
|
||||
"DigitalCommunication",
|
||||
"DutyCycleInput",
|
||||
"EventLoop",
|
||||
"FlywheelBangBangController",
|
||||
"HttpCamera",
|
||||
"I2CCommunication",
|
||||
"IntermediateVision",
|
||||
"MotorControl",
|
||||
"QuickVision",
|
||||
"SelectCommand",
|
||||
"Solenoid",
|
||||
]
|
||||
|
||||
ignored = [
|
||||
]
|
||||
Reference in New Issue
Block a user