Skip to content

Commit bd91553

Browse files
committed
Switch to k-prefix naming convention for constants
1 parent d5ee6f8 commit bd91553

File tree

5 files changed

+56
-56
lines changed

5 files changed

+56
-56
lines changed

digital-communication/robot.py

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -9,18 +9,18 @@
99

1010
class MyRobot(wpilib.TimedRobot):
1111
# define ports for digitalcommunication with light controller
12-
ALLIANCE_PORT = 0
13-
ENABLED_PORT = 1
14-
AUTONOMOUS_PORT = 2
15-
ALERT_PORT = 3
12+
kAlliancePort = 0
13+
kEnabledPort = 1
14+
kAutonomousPort = 2
15+
kAlertPort = 3
1616

1717
def robotInit(self):
1818
"""Robot initialization function"""
1919

20-
self.allianceOutput = wpilib.DigitalOutput(self.ALLIANCE_PORT)
21-
self.enabledOutput = wpilib.DigitalOutput(self.ENABLED_PORT)
22-
self.autonomousOutput = wpilib.DigitalOutput(self.AUTONOMOUS_PORT)
23-
self.alertOutput = wpilib.DigitalOutput(self.ALERT_PORT)
20+
self.allianceOutput = wpilib.DigitalOutput(self.kAlliancePort)
21+
self.enabledOutput = wpilib.DigitalOutput(self.kEnabledPort)
22+
self.autonomousOutput = wpilib.DigitalOutput(self.kAutonomousPort)
23+
self.alertOutput = wpilib.DigitalOutput(self.kAlertPort)
2424

2525
def robotPeriodic(self):
2626
setAlliance = False

flywheel-bangbang-controller/robot.py

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -14,24 +14,24 @@
1414

1515

1616
class MyRobot(wpilib.TimedRobot):
17-
MOTOR_PORT = 0
18-
ENCODER_A_CHANNEL = 0
19-
ENCODER_B_CHANNEL = 1
17+
kMotorPort = 0
18+
kEncoderAChannel = 0
19+
kEncoderBChannel = 1
2020

2121
# Max setpoint for joystick control in RPM
22-
MAX_SETPOINT_VALUE = 6000.0
22+
kMaxSetpointValue = 6000.0
2323

2424
# Gains are for example purposes only - must be determined for your own robot!
25-
FLYWHEEL_KS = 0.0001 # V
26-
FLYWHEEL_KV = 0.000195 # V/RPM
27-
FLYWHEEL_KA = 0.0003 # V/(RPM/s)
25+
kFlywheelKs = 0.0001 # V
26+
kFlywheelKv = 0.000195 # V/RPM
27+
kFlywheelKa = 0.0003 # V/(RPM/s)
2828

2929
# Reduction between motors and encoder, as output over input. If the flywheel
3030
# spins slower than the motors, this number should be greater than one.
31-
FLYWHEEL_GEARING = 1.0
31+
kFlywheelGearing = 1.0
3232

3333
# 1/2 MR²
34-
FLYWHEEL_MOMENT_OF_INERTIA = (
34+
kFlywheelMomentOfInertia = (
3535
0.5
3636
* wpimath.units.lbsToKilograms(1.5)
3737
* math.pow(wpimath.units.inchesToMeters(4), 2)
@@ -41,20 +41,20 @@ def robotInit(self):
4141
"""Robot initialization function"""
4242

4343
self.feedforward = wpimath.controller.SimpleMotorFeedforwardMeters(
44-
self.FLYWHEEL_KS, self.FLYWHEEL_KV, self.FLYWHEEL_KA
44+
self.kFlywheelKs, self.kFlywheelKv, self.kFlywheelKa
4545
)
4646

4747
# Joystick to control setpoint
4848
self.joystick = wpilib.Joystick(0)
4949

50-
self.flywheelMotor = wpilib.PWMSparkMax(self.MOTOR_PORT)
51-
self.encoder = wpilib.Encoder(self.ENCODER_A_CHANNEL, self.ENCODER_B_CHANNEL)
50+
self.flywheelMotor = wpilib.PWMSparkMax(self.kMotorPort)
51+
self.encoder = wpilib.Encoder(self.kEncoderAChannel, self.kEncoderBChannel)
5252

5353
self.bangBangControler = wpimath.controller.BangBangController()
5454

5555
# Simulation classes help us simulate our robot
5656
self.flywheelSim = wpilib.simulation.FlywheelSim(
57-
DCMotor.NEO(1), self.FLYWHEEL_GEARING, self.FLYWHEEL_MOMENT_OF_INERTIA
57+
DCMotor.NEO(1), self.kFlywheelGearing, self.kFlywheelMomentOfInertia
5858
)
5959
self.encoderSim = wpilib.simulation.EncoderSim(self.encoder)
6060

@@ -69,7 +69,7 @@ def teleopPeriodic(self):
6969
0.0,
7070
self.joystick.getRawAxis(0)
7171
* wpimath.units.rotationsPerMinuteToRadiansPerSecond(
72-
self.MAX_SETPOINT_VALUE
72+
self.kMaxSetpointValue
7373
),
7474
)
7575

gyro-mecanum/robot.py

Lines changed: 14 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -11,25 +11,25 @@
1111
class MyRobot(wpilib.TimedRobot):
1212
# gyro calibration constant, may need to be adjusted;
1313
# gyro value of 360 is set to correspond to one full revolution
14-
VOLTS_PER_DEGREE_PER_SECOND = 0.0128
14+
kVoltsPerDegreePerSecond = 0.0128
1515

16-
FRONT_LEFT_CHANNEL = 0
17-
REAR_LEFT_CHANNEL = 1
18-
FRONT_RIGHT_CHANNEL = 2
19-
REAR_RIGHT_CHANNEL = 3
20-
GYRO_PORT = 0
21-
JOYSTICK_PORT = 0
16+
kFrontLeftChannel = 0
17+
kRearLeftChannel = 1
18+
kFrontRightChannel = 2
19+
kRearRightChannel = 3
20+
kGyroPort = 0
21+
kJoystickPort = 0
2222

2323
def robotInit(self):
2424
"""Robot initialization function"""
2525

26-
self.gyro = wpilib.AnalogGyro(self.GYRO_PORT)
27-
self.joystick = wpilib.Joystick(self.JOYSTICK_PORT)
26+
self.gyro = wpilib.AnalogGyro(self.kGyroPort)
27+
self.joystick = wpilib.Joystick(self.kJoystickPort)
2828

29-
frontLeft = wpilib.PWMSparkMax(self.FRONT_LEFT_CHANNEL)
30-
rearLeft = wpilib.PWMSparkMax(self.REAR_LEFT_CHANNEL)
31-
frontRight = wpilib.PWMSparkMax(self.FRONT_RIGHT_CHANNEL)
32-
rearRight = wpilib.PWMSparkMax(self.REAR_RIGHT_CHANNEL)
29+
frontLeft = wpilib.PWMSparkMax(self.kFrontLeftChannel)
30+
rearLeft = wpilib.PWMSparkMax(self.kRearLeftChannel)
31+
frontRight = wpilib.PWMSparkMax(self.kFrontRightChannel)
32+
rearRight = wpilib.PWMSparkMax(self.kRearRightChannel)
3333

3434
frontRight.setInverted(True)
3535
rearRight.setInverted(True)
@@ -38,7 +38,7 @@ def robotInit(self):
3838
frontLeft, rearLeft, frontRight, rearRight
3939
)
4040

41-
self.gyro.setSensitivity(self.VOLTS_PER_DEGREE_PER_SECOND)
41+
self.gyro.setSensitivity(self.kVoltsPerDegreePerSecond)
4242

4343
def teleopPeriodic(self):
4444
self.robotDrive.driveCartesian(

gyro/robot.py

Lines changed: 13 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -16,28 +16,28 @@ class MyRobot(wpilib.TimedRobot):
1616
keeping.
1717
"""
1818

19-
ANGLE_SETPOINT = 0.0
20-
P = 0.005 # propotional turning constant
19+
kAngleSetpoint = 0.0
20+
kP = 0.005 # propotional turning constant
2121

2222
# gyro calibration constant, may need to be adjusted;
2323
# gyro value of 360 is set to correspond to one full revolution
24-
VOLTS_PER_DEGREE_PER_SECOND = 0.0128
24+
kVoltsPerDegreePerSecond = 0.0128
2525

26-
LEFT_MOTOR_PORT = 0
27-
RIGHT_MOTOR_PORT = 1
28-
GYRO_PORT = 0
29-
JOYSTICK_PORT = 0
26+
kLeftMotorPort = 0
27+
kRightMotorPort = 1
28+
kGyroPort = 0
29+
kJoystickPort = 0
3030

3131
def robotInit(self):
3232
"""Robot initialization function"""
3333

34-
self.leftDrive = wpilib.PWMSparkMax(self.LEFT_MOTOR_PORT)
35-
self.rightDrive = wpilib.PWMSparkMax(self.RIGHT_MOTOR_PORT)
34+
self.leftDrive = wpilib.PWMSparkMax(self.kLeftMotorPort)
35+
self.rightDrive = wpilib.PWMSparkMax(self.kRightMotorPort)
3636
self.myRobot = wpilib.drive.DifferentialDrive(self.leftDrive, self.rightDrive)
37-
self.gyro = wpilib.AnalogGyro(self.GYRO_PORT)
38-
self.joystick = wpilib.Joystick(self.JOYSTICK_PORT)
37+
self.gyro = wpilib.AnalogGyro(self.kGyroPort)
38+
self.joystick = wpilib.Joystick(self.kJoystickPort)
3939

40-
self.gyro.setSensitivity(self.VOLTS_PER_DEGREE_PER_SECOND)
40+
self.gyro.setSensitivity(self.kVoltsPerDegreePerSecond)
4141

4242
# We need to invert one side of the drivetrain so that positive voltages
4343
# result in both sides moving forward. Depending on how your robot's
@@ -47,7 +47,7 @@ def robotInit(self):
4747
def teleopPeriodic(self):
4848
# The motor speed is set from the joystick while the DifferentialDrive turning value is assigned
4949
# from the error between the setpoint and the gyro angle.
50-
turningValue = (self.ANGLE_SETPOINT - self.gyro.getAngle()) * self.P
50+
turningValue = (self.kAngleSetpoint - self.gyro.getAngle()) * self.kP
5151
self.myRobot.arcadeDrive(-self.joystick.getY(), -turningValue)
5252

5353

motor-control/robot.py

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -22,17 +22,17 @@ class MyRobot(wpilib.TimedRobot):
2222
to the Dashboard.
2323
"""
2424

25-
MOTOR_PORT = 0
26-
JOYSTICK_PORT = 0
27-
ENCODER_PORT_A = 0
28-
ENCODER_PORT_B = 1
25+
kMotorPort = 0
26+
kJoystickPort = 0
27+
kEncoderPortA = 0
28+
kEncoderPortB = 1
2929

3030
def robotInit(self):
3131
"""Robot initialization function"""
3232

33-
self.motor = wpilib.PWMSparkMax(self.MOTOR_PORT)
34-
self.joystick = wpilib.Joystick(self.JOYSTICK_PORT)
35-
self.encoder = wpilib.Encoder(self.ENCODER_PORT_A, self.ENCODER_PORT_B)
33+
self.motor = wpilib.PWMSparkMax(self.kMotorPort)
34+
self.joystick = wpilib.Joystick(self.kJoystickPort)
35+
self.encoder = wpilib.Encoder(self.kEncoderPortA, self.kEncoderPortB)
3636
# Use SetDistancePerPulse to set the multiplier for GetDistance
3737
# This is set up assuming a 6 inch wheel with a 360 CPR encoder.
3838
self.encoder.setDistancePerPulse((math.pi * 6) / 360.0)

0 commit comments

Comments
 (0)