Skip to content
This repository has been archived by the owner on Jan 10, 2025. It is now read-only.

Commit

Permalink
Fix style, fix unit tests
Browse files Browse the repository at this point in the history
  • Loading branch information
KenwoodFox committed Mar 5, 2024
1 parent 5f4d07a commit 52780b9
Show file tree
Hide file tree
Showing 5 changed files with 11 additions and 7 deletions.
2 changes: 1 addition & 1 deletion rio/commands/intakeRotationMAN.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@


class IntakeRotationMAN(commands2.Command):
def __init__(self, angle: float, _intake:IntakeSubsystem):
def __init__(self, angle: float, _intake: IntakeSubsystem):
"""
allows people to rotate the intake
"""
Expand Down
3 changes: 2 additions & 1 deletion rio/commands/manualRot.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

from subsystems.shooter import Shooter


class manualROT(commands2.Command):
def __init__(self, speed, _shooter: Shooter):
super().__init__()
Expand All @@ -11,7 +12,7 @@ def __init__(self, speed, _shooter: Shooter):

# requested speed
self.speed = speed

# Command requirements
self.addRequirements(self.subsystem)

Expand Down
4 changes: 2 additions & 2 deletions rio/commands/setIntakeSpeed.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ def __init__(self, speed: float, _intake: IntakeSubsystem):

# Command requirements
self.addRequirements(self.intakeSubsystem)

def initialize(self):
logging.debug(f"Running command Intake Suck (manual) with speed {self.speed}")

Expand All @@ -32,7 +32,7 @@ def execute(self):

def isFinished(self):
return True

def end(self, interrupted: bool):
logging.debug(f"Intake suck done")
return True
2 changes: 1 addition & 1 deletion rio/commands/shooterROT.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ def __init__(self, angle: float, _shooter: Shooter):

# requested speed
self.angle = angle

# Command requirements
self.addRequirements(self.subsystem)

Expand Down
7 changes: 5 additions & 2 deletions rio/subsystems/drivesubsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,10 @@ def drive(
xSpeed: float,
ySpeed: float,
rot: float,
fieldRelative: typing.Callable,
fieldRelative: typing.Callable[
[],
bool,
],
rateLimit: bool,
) -> None:
"""Method to drive the robot using joystick info.
Expand Down Expand Up @@ -252,7 +255,7 @@ def drive(
rotDelivered,
Rotation2d.fromDegrees(self.gyro.getAngle()),
)
if fieldRelative()
if fieldRelative
else ChassisSpeeds(xSpeedDelivered, ySpeedDelivered, rotDelivered)
)
fl, fr, rl, rr = SwerveDrive4Kinematics.desaturateWheelSpeeds(
Expand Down

0 comments on commit 52780b9

Please sign in to comment.