Skip to content

Commit b144a30

Browse files
committed
Run black
1 parent e23b98f commit b144a30

15 files changed

Lines changed: 69 additions & 26 deletions

File tree

examples/robot/DifferentialDriveBot/drivetrain.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,9 @@ def __init__(self) -> None:
6868
self.rightEncoder.getDistance(),
6969
)
7070

71-
def setVelocities(self, velocities: wpimath.DifferentialDriveWheelVelocities) -> None:
71+
def setVelocities(
72+
self, velocities: wpimath.DifferentialDriveWheelVelocities
73+
) -> None:
7274
"""Sets the desired wheel velocities.
7375
7476
:param velocities: The desired wheel velocities.

examples/robot/DifferentialDrivePoseEstimator/drivetrain.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -111,7 +111,9 @@ def __init__(self, cameraToObjectTopic: ntcore.DoubleArrayTopic) -> None:
111111
wpilib.SmartDashboard.putData("Field", self.fieldSim)
112112
wpilib.SmartDashboard.putData("FieldEstimation", self.fieldApproximation)
113113

114-
def setVelocities(self, velocities: wpimath.DifferentialDriveWheelVelocities) -> None:
114+
def setVelocities(
115+
self, velocities: wpimath.DifferentialDriveWheelVelocities
116+
) -> None:
115117
"""Sets the desired wheel velocities.
116118
117119
:param velocities: The desired wheel velocities.

examples/robot/HatchbotTraditional/commands/complexauto.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,8 @@ def __init__(self, drive: DriveSubsystem, hatch: HatchSubsystem):
3030
ReleaseHatch(hatch),
3131
# Drive backward the specified distance
3232
DriveDistance(
33-
constants.kAutoBackupDistanceInches, -constants.kAutoDriveVelocity, drive
33+
constants.kAutoBackupDistanceInches,
34+
-constants.kAutoDriveVelocity,
35+
drive,
3436
),
3537
)

examples/robot/MecanumBot/drivetrain.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -114,7 +114,9 @@ def drive(
114114
"""Method to drive the robot using joystick info."""
115115
chassisVelocities = wpimath.ChassisVelocities(xVelocity, yVelocity, rot)
116116
if fieldRelative:
117-
chassisVelocities = chassisVelocities.toRobotRelative(self.imu.getRotation2d())
117+
chassisVelocities = chassisVelocities.toRobotRelative(
118+
self.imu.getRotation2d()
119+
)
118120

119121
self.setVelocities(
120122
self.kinematics.toWheelVelocities(

examples/robot/MecanumDrivePoseEstimator/drivetrain.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -144,9 +144,9 @@ def drive(
144144
self.poseEstimator.getEstimatedPosition().rotation()
145145
)
146146
self.setVelocities(
147-
self.kinematics.toWheelVelocities(chassisVelocities.discretize(period)).desaturate(
148-
self.kMaxVelocity
149-
)
147+
self.kinematics.toWheelVelocities(
148+
chassisVelocities.discretize(period)
149+
).desaturate(self.kMaxVelocity)
150150
)
151151

152152
def updateOdometry(self) -> None:

examples/robot/SimpleDifferentialDriveSimulation/drivetrain.py

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -88,7 +88,9 @@ def __init__(self) -> None:
8888
self.rightLeader.setInverted(True)
8989
wpilib.SmartDashboard.putData("Field", self.fieldSim)
9090

91-
def setVelocities(self, velocities: wpimath.DifferentialDriveWheelVelocities) -> None:
91+
def setVelocities(
92+
self, velocities: wpimath.DifferentialDriveWheelVelocities
93+
) -> None:
9294
"""Sets velocities to the drivetrain motors."""
9395
leftFeedforward = self.feedforward.calculate(velocities.left)
9496
rightFeedforward = self.feedforward.calculate(velocities.right)
@@ -109,7 +111,9 @@ def drive(self, xVelocity: float, rot: float) -> None:
109111
:param rot: the rotation
110112
"""
111113
self.setVelocities(
112-
self.kinematics.toWheelVelocities(wpimath.ChassisVelocities(xVelocity, 0, rot))
114+
self.kinematics.toWheelVelocities(
115+
wpimath.ChassisVelocities(xVelocity, 0, rot)
116+
)
113117
)
114118

115119
def updateOdometry(self) -> None:

examples/robot/StateSpaceArm/robot.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,9 @@ def __init__(self) -> None:
3535
self.profile = wpimath.TrapezoidProfile(
3636
wpimath.TrapezoidProfile.Constraints(
3737
wpimath.units.degreesToRadians(45),
38-
wpimath.units.degreesToRadians(90), # Max arm velocity and acceleration.
38+
wpimath.units.degreesToRadians(
39+
90
40+
), # Max arm velocity and acceleration.
3941
)
4042
)
4143

examples/robot/StateSpaceElevator/robot.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,9 @@ def __init__(self) -> None:
3939
self.profile = wpimath.TrapezoidProfile(
4040
wpimath.TrapezoidProfile.Constraints(
4141
wpimath.units.feetToMeters(3.0),
42-
wpimath.units.feetToMeters(6.0), # Max elevator velocity and acceleration.
42+
wpimath.units.feetToMeters(
43+
6.0
44+
), # Max elevator velocity and acceleration.
4345
)
4446
)
4547

examples/robot/SwerveBot/drivetrain.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,9 @@ def drive(
6969
"""
7070
robot_velocities = wpimath.ChassisVelocities(xVelocity, yVelocity, rot)
7171
if fieldRelative:
72-
robot_velocities = robot_velocities.toRobotRelative(self.imu.getRotation2d())
72+
robot_velocities = robot_velocities.toRobotRelative(
73+
self.imu.getRotation2d()
74+
)
7375

7476
swerveModuleStates = self.kinematics.toSwerveModuleVelocities(
7577
wpimath.ChassisVelocities.discretize(robot_velocities, periodSeconds)

examples/robot/SwerveDrivePoseEstimator/drivetrain.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -82,7 +82,9 @@ def drive(
8282
chassisVelocities = chassisVelocities.discretize(period)
8383

8484
states = self.kinematics.toSwerveModuleVelocities(chassisVelocities)
85-
wpimath.SwerveDrive4Kinematics.desaturateWheelVelocities(states, self.kMaxVelocity)
85+
wpimath.SwerveDrive4Kinematics.desaturateWheelVelocities(
86+
states, self.kMaxVelocity
87+
)
8688

8789
self.frontLeft.setDesiredVelocity(states[0])
8890
self.frontRight.setDesiredVelocity(states[1])

0 commit comments

Comments
 (0)