From 0a3777b769915d3bac740d91e2050ed974915b3d Mon Sep 17 00:00:00 2001 From: Guilherme Samuel Date: Thu, 29 Feb 2024 16:10:22 -0300 Subject: [PATCH] style: format with black --- 2023-base-code/version1/robot.py | 2 - 2023-base-code/version2/robot.py | 2 - 2023-base-code/version3-offseason/robot.py | 52 ++++++++++++---------- 2023-photonvision/robot.py | 8 +++- drive/drivetrain-navX/robot.py | 1 - navX/robot.py | 2 +- networktables/using_keyboard.py | 6 +-- smartdashboard/combobox/robot.py | 1 + smartdashboard/robot.py | 1 + 9 files changed, 41 insertions(+), 34 deletions(-) diff --git a/2023-base-code/version1/robot.py b/2023-base-code/version1/robot.py index 844892e..2b0c3ab 100644 --- a/2023-base-code/version1/robot.py +++ b/2023-base-code/version1/robot.py @@ -94,12 +94,10 @@ def robotInit(self): self.stick = wpilib.Joystick(0) def teleopInit(self): - self.myRobot.setSafetyEnabled(True) self.compressor.disable() def teleopPeriodic(self): - self.myRobot.arcadeDrive( self.stick.getRawAxis(1), self.stick.getRawAxis(0) * 1.15, True ) diff --git a/2023-base-code/version2/robot.py b/2023-base-code/version2/robot.py index 6655c20..d81c1c8 100644 --- a/2023-base-code/version2/robot.py +++ b/2023-base-code/version2/robot.py @@ -77,12 +77,10 @@ def robotInit(self): self.stick = wpilib.Joystick(0) def teleopInit(self): - self.myRobot.setSafetyEnabled(True) self.compressor.disable() def teleopPeriodic(self): - self.myRobot.arcadeDrive( self.stick.getRawAxis(1), self.stick.getRawAxis(0) * 1.15, True ) diff --git a/2023-base-code/version3-offseason/robot.py b/2023-base-code/version3-offseason/robot.py index 1c17c5f..92b6877 100644 --- a/2023-base-code/version3-offseason/robot.py +++ b/2023-base-code/version3-offseason/robot.py @@ -3,6 +3,7 @@ import ctre import rev + class Taubatexas(wpilib.TimedRobot): def robotInit(self): # Drivetrain @@ -21,7 +22,9 @@ def robotInit(self): self.intake_bar_left = ctre.WPI_VictorSPX(5) self.intake_bar_right = ctre.WPI_VictorSPX(12) self.intake_bar_right.setInverted(True) - self.intake = wpilib.MotorControllerGroup(self.intake_bar_left, self.intake_bar_right) + self.intake = wpilib.MotorControllerGroup( + self.intake_bar_left, self.intake_bar_right + ) # Arm self.length = rev.CANSparkMax(52, rev.CANSparkMaxLowLevel.MotorType.kBrushless) @@ -40,25 +43,27 @@ def robotInit(self): self.smartdashboard.putNumber("Intake Right", 0.25) self.smartdashboard.putNumber("Arm Length Speed", 1) self.smartdashboard.putNumber("Arm Angle Duty Cycle", 0.15) - + # Joystick self.joystick = wpilib.Joystick(0) # Timer self.timer = wpilib.Timer() - #self.angle_encoder.setPosition(0) + # self.angle_encoder.setPosition(0) def robotPeriodic(self): - self.smartdashboard.putNumber('Arm Angle Encoder', self.angle_encoder.getPosition()) + self.smartdashboard.putNumber( + "Arm Angle Encoder", self.angle_encoder.getPosition() + ) def getSpecificAxis(self): if self.joystick.getRawAxis(4) > 0: - return self.joystick.getRawAxis(4) + return self.joystick.getRawAxis(4) elif self.joystick.getRawAxis(3) > 0: - return -self.joystick.getRawAxis(3) + return -self.joystick.getRawAxis(3) else: - return 0 + return 0 def setIntake(self, left: float, right: float): self.intake_bar_left.set(left) @@ -74,23 +79,23 @@ def teleopPeriodic(self): ) if self.joystick.getRawButton(1): - #self.intake.set(0.5) + # self.intake.set(0.5) self.setIntake( -self.smartdashboard.getNumber("Intake Left", 0.25), - -self.smartdashboard.getNumber("Intake Right", 0.25) + -self.smartdashboard.getNumber("Intake Right", 0.25), ) elif self.joystick.getRawButton(2): - #self.intake.set(-0.5) + # self.intake.set(-0.5) self.setIntake( self.smartdashboard.getNumber("Intake Left", 0.25), - self.smartdashboard.getNumber("Intake Right", 0.25) + self.smartdashboard.getNumber("Intake Right", 0.25), ) elif self.joystick.getRawButton(9): self.intake_bar_left.set(0.1) elif self.joystick.getRawButton(10): self.intake_bar_right.set(0.1) else: - #self.intake.set(0) + # self.intake.set(0) self.setIntake(0, 0) if self.joystick.getRawButton(5): @@ -102,25 +107,24 @@ def teleopPeriodic(self): if self.joystick.getRawButton(4): self.angle_pid.setReference( - self.smartdashboard.getNumber('Arm Angle Duty Cycle', 0.15), - rev.CANSparkMax.ControlType.kDutyCycle + self.smartdashboard.getNumber("Arm Angle Duty Cycle", 0.15), + rev.CANSparkMax.ControlType.kDutyCycle, ) self.position = self.angle_encoder.getPosition() elif self.joystick.getRawButton(3): self.angle_pid.setReference( - -self.smartdashboard.getNumber('Arm Angle Duty Cycle', 0.15), - rev.CANSparkMax.ControlType.kDutyCycle + -self.smartdashboard.getNumber("Arm Angle Duty Cycle", 0.15), + rev.CANSparkMax.ControlType.kDutyCycle, ) self.position = self.angle_encoder.getPosition() else: self.angle_pid.setReference( - self.position, - rev.CANSparkMax.ControlType.kPosition + self.position, rev.CANSparkMax.ControlType.kPosition ) - - #def disabledInit(self): + + # def disabledInit(self): # self.angle_encoder.setPosition(0) - ''' + """ def disabledPeriodic(self): if(self.timer.get() < 5) self.angle_pid.setReference( @@ -129,6 +133,8 @@ def disabledPeriodic(self): ) else: self.timer.stop() - ''' + """ + + if __name__ == "__main__": - wpilib.run(Taubatexas) \ No newline at end of file + wpilib.run(Taubatexas) diff --git a/2023-photonvision/robot.py b/2023-photonvision/robot.py index 222c607..1b76cc7 100644 --- a/2023-photonvision/robot.py +++ b/2023-photonvision/robot.py @@ -13,8 +13,12 @@ def robotInit(self): constants.kP, constants.kI, constants.kD ) self.drive = wpilib.drive.DifferentialDrive( - wpilib.MotorControllerGroup(phoenix5.WPI_VictorSPX(0), phoenix5.WPI_VictorSPX(1)), - wpilib.MotorControllerGroup(phoenix5.WPI_VictorSPX(2), phoenix5.WPI_VictorSPX(3)), + wpilib.MotorControllerGroup( + phoenix5.WPI_VictorSPX(0), phoenix5.WPI_VictorSPX(1) + ), + wpilib.MotorControllerGroup( + phoenix5.WPI_VictorSPX(2), phoenix5.WPI_VictorSPX(3) + ), ) def robotPeriodic(self): diff --git a/drive/drivetrain-navX/robot.py b/drive/drivetrain-navX/robot.py index 07c685e..335f929 100644 --- a/drive/drivetrain-navX/robot.py +++ b/drive/drivetrain-navX/robot.py @@ -63,7 +63,6 @@ def autonomousInit(self): pass def autonomousPeriodic(self): - # self.m_left_front.set(0.6) # self.m_right_front.set(0.6) # self.m_right_back.set(0.6) diff --git a/navX/robot.py b/navX/robot.py index 73d03bc..974ab88 100644 --- a/navX/robot.py +++ b/navX/robot.py @@ -57,7 +57,7 @@ def teleopInit(self): def autonomousPeriodic(self): yaw = self.navx.getAngle() - #print(yaw) + # print(yaw) def teleopPeriodic(self): pass diff --git a/networktables/using_keyboard.py b/networktables/using_keyboard.py index bed747e..fbbd31e 100644 --- a/networktables/using_keyboard.py +++ b/networktables/using_keyboard.py @@ -1,6 +1,6 @@ import time -import ntcore # pip install robotpy -import keyboard # pip install keyboard +import ntcore # pip install robotpy +import keyboard # pip install keyboard inst = ntcore.NetworkTableInstance.getDefault() table = inst.getTable("keyboard") @@ -18,4 +18,4 @@ while True: event = keyboard.read_event() if event.name: - table.putBoolean(event.name, event.event_type == keyboard.KEY_DOWN) \ No newline at end of file + table.putBoolean(event.name, event.event_type == keyboard.KEY_DOWN) diff --git a/smartdashboard/combobox/robot.py b/smartdashboard/combobox/robot.py index e01ef8d..a576a16 100644 --- a/smartdashboard/combobox/robot.py +++ b/smartdashboard/combobox/robot.py @@ -13,6 +13,7 @@ @dataclass class Option: """Class for keeping track of an item in inventory.""" + name: str diff --git a/smartdashboard/robot.py b/smartdashboard/robot.py index bd49ba3..8932c8e 100644 --- a/smartdashboard/robot.py +++ b/smartdashboard/robot.py @@ -2,6 +2,7 @@ import wpilib import phoenix5 + class EasyNetworkTableExample(wpilib.TimedRobot): def robotInit(self) -> None: inst = ntcore.NetworkTableInstance.getDefault()