Skip to content

Commit 3c6757b

Browse files
authored
Merge pull request #91 from fletch3555/low-hanging-fruit
low hanging fruit
2 parents 4cfe0b1 + 61f2f7c commit 3c6757b

File tree

21 files changed

+763
-125
lines changed

21 files changed

+763
-125
lines changed

arcade-drive-xbox-controller/robot.py

Lines changed: 4 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -18,20 +18,15 @@ class MyRobot(wpilib.TimedRobot):
1818
def robotInit(self):
1919
"""Robot initialization function"""
2020

21-
# create motor controller objects
22-
left = wpilib.PWMSparkMax(0)
23-
right = wpilib.PWMSparkMax(1)
24-
25-
# object that handles basic drive operations
26-
self.robotDrive = wpilib.drive.DifferentialDrive(left, right)
27-
28-
# xbox controller 0 on the driver station
21+
leftMotor = wpilib.PWMSparkMax(0)
22+
rightMotor = wpilib.PWMSparkMax(1)
23+
self.robotDrive = wpilib.drive.DifferentialDrive(leftMotor, rightMotor)
2924
self.driverController = wpilib.XboxController(0)
3025

3126
# We need to invert one side of the drivetrain so that positive voltages
3227
# result in both sides moving forward. Depending on how your robot's
3328
# gearbox is constructed, you might have to invert the left side instead.
34-
right.setInverted(True)
29+
rightMotor.setInverted(True)
3530

3631
def teleopPeriodic(self):
3732
# Drive with split arcade style

arcade-drive/robot.py

Lines changed: 8 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -18,26 +18,21 @@ class MyRobot(wpilib.TimedRobot):
1818
def robotInit(self):
1919
"""Robot initialization function"""
2020

21-
# create motor controller objects
22-
left = wpilib.PWMSparkMax(0)
23-
right = wpilib.PWMSparkMax(1)
24-
25-
# object that handles basic drive operations
26-
self.robotDrive = wpilib.drive.DifferentialDrive(left, right)
27-
28-
# joystick 0 on the driver station
21+
leftMotor = wpilib.PWMSparkMax(0)
22+
rightMotor = wpilib.PWMSparkMax(1)
23+
self.robotDrive = wpilib.drive.DifferentialDrive(leftMotor, rightMotor)
2924
self.stick = wpilib.Joystick(0)
3025

3126
# We need to invert one side of the drivetrain so that positive voltages
3227
# result in both sides moving forward. Depending on how your robot's
3328
# gearbox is constructed, you might have to invert the left side instead.
34-
right.setInverted(True)
29+
rightMotor.setInverted(True)
3530

3631
def teleopPeriodic(self):
37-
# Drive with split arcade style
38-
# That means that the Y axis of the left stick moves forward
39-
# and backward, and the X of the right stick turns left and right.
40-
self.robotDrive.arcadeDrive(-self.stick.getY(), -self.stick.getX())
32+
# Drive with arcade drive.
33+
# That means that the Y axis drives forward
34+
# and backward, and the X turns left and right.
35+
self.robotDrive.arcadeDrive(self.stick.getY(), self.stick.getX())
4136

4237

4338
if __name__ == "__main__":

canpdp/robot.py

Lines changed: 0 additions & 1 deletion
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):

digital-communication/robot.py

Lines changed: 52 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
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+
import wpilib
9+
10+
11+
class MyRobot(wpilib.TimedRobot):
12+
"""
13+
This is a sample program demonstrating how to communicate to a light controller from the robot
14+
code using the roboRIO's DIO ports.
15+
"""
16+
17+
# define ports for digitalcommunication with light controller
18+
kAlliancePort = 0
19+
kEnabledPort = 1
20+
kAutonomousPort = 2
21+
kAlertPort = 3
22+
23+
def robotInit(self):
24+
"""Robot initialization function"""
25+
26+
self.allianceOutput = wpilib.DigitalOutput(self.kAlliancePort)
27+
self.enabledOutput = wpilib.DigitalOutput(self.kEnabledPort)
28+
self.autonomousOutput = wpilib.DigitalOutput(self.kAutonomousPort)
29+
self.alertOutput = wpilib.DigitalOutput(self.kAlertPort)
30+
31+
def robotPeriodic(self):
32+
setAlliance = False
33+
alliance = wpilib.DriverStation.getAlliance()
34+
if alliance:
35+
setAlliance = alliance == wpilib.DriverStation.Alliance.kRed
36+
37+
# pull alliance port high if on red alliance, pull low if on blue alliance
38+
self.allianceOutput.set(setAlliance)
39+
40+
# pull enabled port high if enabled, low if disabled
41+
self.enabledOutput.set(wpilib.DriverStation.isEnabled())
42+
43+
# pull auto port high if in autonomous, low if in teleop (or disabled)
44+
self.autonomousOutput.set(wpilib.DriverStation.isAutonomous())
45+
46+
# pull alert port high if match time remaining is between 30 and 25 seconds
47+
matchTime = wpilib.DriverStation.getMatchTime()
48+
self.alertOutput.set(30 >= matchTime >= 25)
49+
50+
51+
if __name__ == "__main__":
52+
wpilib.run(MyRobot)

dutycycle-encoder/robot.py

Lines changed: 39 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,39 @@
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+
import wpilib
9+
10+
11+
class MyRobot(wpilib.TimedRobot):
12+
def robotInit(self):
13+
"""Robot initialization function"""
14+
15+
self.dutyCycleEncoder = wpilib.DutyCycleEncoder(0)
16+
17+
self.dutyCycleEncoder.setDistancePerRotation(0.5)
18+
19+
def robotPeriodic(self):
20+
# Connected can be checked, and uses the frequency of the encoder
21+
connected = self.dutyCycleEncoder.isConnected()
22+
23+
# Duty Cycle Frequency in Hz
24+
frequency = self.dutyCycleEncoder.getFrequency()
25+
26+
# Output of encoder
27+
output = self.dutyCycleEncoder.get()
28+
29+
# Output scaled by DistancePerPulse
30+
distance = self.dutyCycleEncoder.getDistance()
31+
32+
wpilib.SmartDashboard.putBoolean("Connected", connected)
33+
wpilib.SmartDashboard.putNumber("Frequency", frequency)
34+
wpilib.SmartDashboard.putNumber("Output", output)
35+
wpilib.SmartDashboard.putNumber("Distance", distance)
36+
37+
38+
if __name__ == "__main__":
39+
wpilib.run(MyRobot)

dutycycle-input/robot.py

Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
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+
import wpilib
9+
10+
11+
class MyRobot(wpilib.TimedRobot):
12+
def robotInit(self):
13+
"""Robot initialization function"""
14+
15+
self.dutyCycle = wpilib.DutyCycle(wpilib.DigitalInput(0))
16+
17+
def robotPeriodic(self):
18+
# Duty Cycle Frequency in Hz
19+
frequency = self.dutyCycle.getFrequency()
20+
21+
# Output of duty cycle, ranging from 0 to 1
22+
# 1 is fully on, 0 is fully off
23+
output = self.dutyCycle.getOutput()
24+
25+
wpilib.SmartDashboard.putNumber("Frequency", frequency)
26+
wpilib.SmartDashboard.putNumber("Duty Cycle", output)
27+
28+
29+
if __name__ == "__main__":
30+
wpilib.run(MyRobot)

encoder/robot.py

Lines changed: 57 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
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+
import wpilib
9+
10+
import math
11+
12+
13+
class MyRobot(wpilib.TimedRobot):
14+
"""
15+
Sample program displaying the value of a quadrature encoder on the SmartDashboard. Quadrature
16+
Encoders are digital sensors which can detect the amount the encoder has rotated since starting
17+
as well as the direction in which the encoder shaft is rotating. However, encoders can not tell
18+
you the absolute position of the encoder shaft (ie, it considers where it starts to be the zero
19+
position, no matter where it starts), and so can only tell you how much the encoder has rotated
20+
since starting. Depending on the precision of an encoder, it will have fewer or greater ticks per
21+
revolution; the number of ticks per revolution will affect the conversion between ticks and
22+
distance, as specified by DistancePerPulse. One of the most common uses of encoders is in the
23+
drivetrain, so that the distance that the robot drives can be precisely controlled during the
24+
autonomous mode.
25+
"""
26+
27+
def robotInit(self):
28+
"""Robot initialization function"""
29+
30+
self.encoder = wpilib.Encoder(1, 2, False, wpilib.Encoder.EncodingType.k4X)
31+
32+
# Defines the number of samples to average when determining the rate.
33+
# On a quadrature encoder, values range from 1-255;
34+
# larger values result in smoother but potentially
35+
# less accurate rates than lower values.
36+
self.encoder.setSamplesToAverage(5)
37+
38+
# Defines how far the mechanism attached to the encoder moves per pulse. In
39+
# this case, we assume that a 360 count encoder is directly
40+
# attached to a 3 inch diameter (1.5inch radius) wheel,
41+
# and that we want to measure distance in inches.
42+
self.encoder.setDistancePerPulse(1.0 / 360.0 * 2.0 * math.pi * 1.5)
43+
44+
# Defines the lowest rate at which the encoder will
45+
# not be considered stopped, for the purposes of
46+
# the GetStopped() method. Units are in distance / second,
47+
# where distance refers to the units of distance
48+
# that you are using, in this case inches.
49+
self.encoder.setMinRate(1.0)
50+
51+
def teleopPeriodic(self):
52+
wpilib.SmartDashboard.putNumber("Encoder Distance", self.encoder.getDistance())
53+
wpilib.SmartDashboard.putNumber("Encoder Rate", self.encoder.getRate())
54+
55+
56+
if __name__ == "__main__":
57+
wpilib.run(MyRobot)
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 wpilib.simulation
8+
from wpimath.system.plant import DCMotor
9+
10+
from pyfrc.physics.core import PhysicsInterface
11+
12+
import typing
13+
14+
if typing.TYPE_CHECKING:
15+
from robot import MyRobot
16+
17+
18+
class PhysicsEngine:
19+
"""
20+
Simulates a flywheel
21+
"""
22+
23+
def __init__(self, physics_controller: PhysicsInterface, robot: "MyRobot"):
24+
"""
25+
:param physics_controller: `pyfrc.physics.core.Physics` object
26+
to communicate simulation effects to
27+
"""
28+
29+
self.physics_controller = physics_controller
30+
31+
# Motors
32+
self.flywheelMotor = wpilib.simulation.PWMSim(robot.flywheelMotor.getChannel())
33+
34+
# Sensors
35+
self.encoder = wpilib.simulation.EncoderSim(robot.encoder)
36+
37+
# Flywheel
38+
self.flywheel = wpilib.simulation.FlywheelSim(
39+
DCMotor.NEO(1), robot.kFlywheelGearing, robot.kFlywheelMomentOfInertia
40+
)
41+
42+
def update_sim(self, now: float, tm_diff: float) -> None:
43+
"""
44+
Called when the simulation parameters for the program need to be
45+
updated.
46+
47+
:param now: The current time as a float
48+
:param tm_diff: The amount of time that has passed since the last
49+
time that this function was called
50+
"""
51+
52+
# To update our simulation, we set motor voltage inputs, update the
53+
# simulation, and write the simulated velocities to our simulated encoder
54+
self.flywheel.setInputVoltage(
55+
self.flywheelMotor.getSpeed() * wpilib.RobotController.getInputVoltage()
56+
)
57+
self.flywheel.update(0.02)
58+
self.encoder.setRate(self.flywheel.getAngularVelocity())

flywheel-bangbang-controller/robot.py

Lines changed: 89 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,89 @@
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+
import wpilib
9+
import wpilib.simulation
10+
import wpimath.controller
11+
import wpimath.units
12+
13+
import math
14+
15+
16+
class MyRobot(wpilib.TimedRobot):
17+
"""
18+
This is a sample program to demonstrate the use of a BangBangController with a flywheel to
19+
control RPM.
20+
"""
21+
22+
kMotorPort = 0
23+
kEncoderAChannel = 0
24+
kEncoderBChannel = 1
25+
26+
# Max setpoint for joystick control in RPM
27+
kMaxSetpointValue = 6000.0
28+
29+
# Gains are for example purposes only - must be determined for your own robot!
30+
kFlywheelKs = 0.0001 # V
31+
kFlywheelKv = 0.000195 # V/RPM
32+
kFlywheelKa = 0.0003 # V/(RPM/s)
33+
34+
# Reduction between motors and encoder, as output over input. If the flywheel
35+
# spins slower than the motors, this number should be greater than one.
36+
kFlywheelGearing = 1.0
37+
38+
# 1/2 MR²
39+
kFlywheelMomentOfInertia = (
40+
0.5
41+
* wpimath.units.lbsToKilograms(1.5)
42+
* math.pow(wpimath.units.inchesToMeters(4), 2)
43+
)
44+
45+
def robotInit(self):
46+
"""Robot initialization function"""
47+
48+
self.feedforward = wpimath.controller.SimpleMotorFeedforwardMeters(
49+
self.kFlywheelKs, self.kFlywheelKv, self.kFlywheelKa
50+
)
51+
52+
# Joystick to control setpoint
53+
self.joystick = wpilib.Joystick(0)
54+
55+
self.flywheelMotor = wpilib.PWMSparkMax(self.kMotorPort)
56+
self.encoder = wpilib.Encoder(self.kEncoderAChannel, self.kEncoderBChannel)
57+
58+
self.bangBangControler = wpimath.controller.BangBangController()
59+
60+
# Add bang-bang controler to SmartDashboard and networktables.
61+
wpilib.SmartDashboard.putData(self.bangBangControler)
62+
63+
def teleopPeriodic(self):
64+
"""Controls flywheel to a set speed (RPM) controlled by a joystick."""
65+
66+
# Scale setpoint value between 0 and maxSetpointValue
67+
setpoint = max(
68+
0.0,
69+
self.joystick.getRawAxis(0)
70+
* wpimath.units.rotationsPerMinuteToRadiansPerSecond(
71+
self.kMaxSetpointValue
72+
),
73+
)
74+
75+
# Set setpoint and measurement of the bang-bang controller
76+
bangOutput = (
77+
self.bangBangControler.calculate(self.encoder.getRate(), setpoint) * 12.0
78+
)
79+
80+
# Controls a motor with the output of the BangBang controller and a
81+
# feedforward. The feedforward is reduced slightly to avoid overspeeding
82+
# the shooter.
83+
self.flywheelMotor.setVoltage(
84+
bangOutput + 0.9 * self.feedforward.calculate(setpoint)
85+
)
86+
87+
88+
if __name__ == "__main__":
89+
wpilib.run(MyRobot)

0 commit comments

Comments
 (0)