Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ruff: Enable isort #19

Merged
merged 2 commits into from
Dec 3, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
39 changes: 20 additions & 19 deletions components/chassis.py
Original file line number Diff line number Diff line change
@@ -1,38 +1,39 @@
from logging import Logger
import math
from logging import Logger

from phoenix6.hardware import TalonFX, CANcoder
from phoenix6.controls import VoltageOut, VelocityVoltage, PositionDutyCycle
from phoenix6.signals import InvertedValue, NeutralModeValue
import magicbot
import navx
import ntcore
import wpilib
from magicbot import feedback
from phoenix6.configs import (
ClosedLoopGeneralConfigs,
MotorOutputConfigs,
FeedbackConfigs,
MotorOutputConfigs,
Slot0Configs,
)
import magicbot
import navx
import ntcore
import wpilib
from phoenix6.controls import PositionDutyCycle, VelocityVoltage, VoltageOut
from phoenix6.hardware import CANcoder, TalonFX
from phoenix6.signals import InvertedValue, NeutralModeValue
from wpimath.controller import (
ProfiledPIDControllerRadians,
SimpleMotorFeedforwardMeters,
)
from wpimath.estimator import SwerveDrive4PoseEstimator
from wpimath.geometry import Pose2d, Rotation2d, Translation2d
from wpimath.kinematics import (
SwerveDrive4Kinematics,
ChassisSpeeds,
SwerveModuleState,
SwerveDrive4Kinematics,
SwerveModulePosition,
SwerveModuleState,
)
from wpimath.geometry import Translation2d, Rotation2d, Pose2d
from wpimath.estimator import SwerveDrive4PoseEstimator
from wpimath.controller import SimpleMotorFeedforwardMeters
from wpimath.trajectory import TrapezoidProfileRadians
from wpimath.controller import ProfiledPIDControllerRadians

from magicbot import feedback

from ids import CancoderId, TalonId
from utilities.ctre import FALCON_FREE_RPS
from utilities.functions import rate_limit_module
from utilities.game import is_red
from utilities.ctre import FALCON_FREE_RPS
from utilities.position import TeamPoses
from ids import CancoderId, TalonId


class SwerveModule:
Expand Down
4 changes: 2 additions & 2 deletions components/vision.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,11 @@

import wpilib
import wpiutil.log
from magicbot import tunable, feedback
from magicbot import feedback, tunable
from photonlibpy import PhotonCamera
from photonlibpy.targeting import PhotonTrackedTarget
from wpimath import objectToRobotPose
from wpimath.geometry import Pose2d, Rotation3d, Transform3d, Translation3d, Pose3d
from wpimath.geometry import Pose2d, Pose3d, Rotation3d, Transform3d, Translation3d

from components.chassis import ChassisComponent
from utilities.game import apriltag_layout
Expand Down
2 changes: 1 addition & 1 deletion physics.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,12 @@
import phoenix6
import phoenix6.unmanaged
import wpilib
from photonlibpy.simulation import PhotonCameraSim, SimCameraProperties, VisionSystemSim
from pyfrc.physics.core import PhysicsInterface
from wpilib.simulation import DCMotorSim, SimDeviceSim
from wpimath.kinematics import SwerveDrive4Kinematics
from wpimath.system.plant import DCMotor, LinearSystemId
from wpimath.units import kilogram_square_meters
from photonlibpy.simulation import PhotonCameraSim, SimCameraProperties, VisionSystemSim

from components.chassis import SwerveModule
from utilities import game
Expand Down
2 changes: 2 additions & 0 deletions pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,8 @@ select = [
"F",
# flake8-bugbear
"B",
# isort
"I",
# pyupgrade
"UP",
# flake8-comprehensions
Expand Down
7 changes: 3 additions & 4 deletions robot.py
Original file line number Diff line number Diff line change
@@ -1,14 +1,13 @@
import math

import magicbot
import wpilib
import wpilib.event
from wpimath.geometry import Rotation3d, Translation3d
import magicbot
from magicbot import tunable
from wpimath.geometry import Rotation3d, Translation3d

from components.chassis import ChassisComponent
from components.vision import VisualLocalizer


from utilities.game import is_red
from utilities.scalers import rescale_js

Expand Down
1 change: 1 addition & 0 deletions tests/test_constrain_angle.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
import math

import pytest
from hypothesis import given
from hypothesis.strategies import floats
Expand Down
6 changes: 3 additions & 3 deletions tests/test_functions.py
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
from math import sin, cos, hypot
from pytest import approx
from math import cos, hypot, sin

from hypothesis import given
from hypothesis.strategies import floats, tuples
from pytest import approx

from utilities.functions import clamp_2d, rate_limit_2d


sensible_floats = floats(allow_infinity=False, allow_nan=False, width=16)
sensible_positive_floats = floats(
min_value=0, allow_infinity=False, allow_nan=False, width=16
Expand Down
3 changes: 2 additions & 1 deletion utilities/functions.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
import math
from wpimath.kinematics import SwerveModuleState

from wpimath.geometry import Rotation2d
from wpimath.kinematics import SwerveModuleState


def constrain_angle(angle: float) -> float:
Expand Down
4 changes: 3 additions & 1 deletion utilities/position.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
import math
from wpimath.geometry import Pose2d, Translation2d, Rotation2d

from wpimath.geometry import Pose2d, Rotation2d, Translation2d

from utilities.game import field_flip_pose2d


Expand Down