diff --git a/.git-blame-ignore-revs b/.git-blame-ignore-revs new file mode 100644 index 00000000..9c8b9e07 --- /dev/null +++ b/.git-blame-ignore-revs @@ -0,0 +1,4 @@ +# dos2unix tests +728f9f2d8ee4aa18b5dcc3d114e64fdd21904bce +# dos2unix utilities +498f22fb696fe7ac146c45a0d9e3c50d2abb0935 diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 37d8fdfa..4203b4b8 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -22,7 +22,7 @@ repos: - id: check-yaml - repo: https://github.com/astral-sh/ruff-pre-commit - rev: v0.9.2 + rev: v0.9.3 hooks: - id: ruff args: diff --git a/controllers/reef_intake.py b/controllers/reef_intake.py index e3139dda..5282c1bb 100644 --- a/controllers/reef_intake.py +++ b/controllers/reef_intake.py @@ -16,6 +16,8 @@ class ReefIntake(StateMachine): L2_INTAKE_ANGLE = tunable(math.radians(-40.0)) L3_INTAKE_ANGLE = tunable(math.radians(-10.0)) + RETREAT_DISTANCE = tunable(0.6) + def __init__(self): self.last_l3 = False @@ -24,9 +26,12 @@ def intake(self) -> None: @state(first=True, must_finish=True) def intaking(self, initial_call: bool): - if self.algae_manipulator_component.has_algae(): + if self.algae_manipulator_component.has_algae() and initial_call: self.done() return + elif self.algae_manipulator_component.has_algae(): + self.next_state("safing") + return current_is_L3 = self.is_L3() @@ -39,6 +44,17 @@ def intaking(self, initial_call: bool): self.algae_manipulator_component.intake() + @state(must_finish=True) + def safing(self, initial_call: bool): + if initial_call: + self.origin_robot_pose = self.chassis.get_pose() + robot_pose = self.chassis.get_pose() + + distance = self.origin_robot_pose.translation() - robot_pose.translation() + + if distance.norm() >= self.RETREAT_DISTANCE: + self.done() + @feedback def is_L3(self) -> bool: return game.is_L3(game.nearest_reef_tag(self.chassis.get_pose())) diff --git a/tests/autonomous_test.py b/tests/autonomous_test.py index 0fb4ecd8..6e50cda9 100644 --- a/tests/autonomous_test.py +++ b/tests/autonomous_test.py @@ -1,18 +1,18 @@ -import hal -import pytest -from robotpy_ext.autonomous.selector_tests import ( # type: ignore[import-untyped] - test_all_autonomous as _test_all_autonomous, -) -from wpilib.simulation import DriverStationSim - - -@pytest.mark.slow_integration_test -@pytest.mark.parametrize("alliance", ["Red", "Blue"]) -def test_all_autonomous(control, alliance): - station = getattr(hal.AllianceStationID, f"k{alliance}1") - DriverStationSim.setAllianceStationId(station) - - _test_all_autonomous(control) - - # Clean up the global simulation state we set. - DriverStationSim.setAllianceStationId(hal.AllianceStationID.kUnknown) +import hal +import pytest +from robotpy_ext.autonomous.selector_tests import ( # type: ignore[import-untyped] + test_all_autonomous as _test_all_autonomous, +) +from wpilib.simulation import DriverStationSim + + +@pytest.mark.slow_integration_test +@pytest.mark.parametrize("alliance", ["Red", "Blue"]) +def test_all_autonomous(control, alliance): + station = getattr(hal.AllianceStationID, f"k{alliance}1") + DriverStationSim.setAllianceStationId(station) + + _test_all_autonomous(control) + + # Clean up the global simulation state we set. + DriverStationSim.setAllianceStationId(hal.AllianceStationID.kUnknown) diff --git a/tests/fuzz_test.py b/tests/fuzz_test.py index 79de9516..1eb2d250 100644 --- a/tests/fuzz_test.py +++ b/tests/fuzz_test.py @@ -1,146 +1,146 @@ -from __future__ import annotations - -import os -import random -import typing - -import hal -import pytest -import wpilib.simulation -from wpilib.simulation import DriverStationSim - -if typing.TYPE_CHECKING: - from pyfrc.test_support.controller import TestController - -pytestmark = pytest.mark.integration_test - - -def rand_bool() -> bool: - return random.getrandbits(1) != 0 - - -def rand_axis() -> float: - """Get a random number between -1 and 1.""" - return random.random() * 2 - 1 - - -def rand_pov() -> int: - """Pick a random POV hat value.""" - return random.choice((-1, 0, 45, 90, 135, 180, 225, 270, 315)) - - -class AllTheThings: - """Fuzzer for robot hardware inputs.""" - - def __init__(self) -> None: - self.dios = [ - dio - for dio in map(wpilib.simulation.DIOSim, range(hal.getNumDigitalChannels())) - if dio.getInitialized() - ] - - def fuzz(self) -> None: - for dio in self.dios: - if dio.getIsInput(): # pragma: no branch - dio.setValue(rand_bool()) - - -class DSInputs: - """Fuzzer for HIDs attached to the driver station.""" - - def __init__(self) -> None: - self.gamepad = wpilib.simulation.XboxControllerSim(0) - self.joystick = wpilib.simulation.JoystickSim(1) - - def fuzz(self) -> None: - fuzz_xbox_gamepad(self.gamepad) - fuzz_joystick(self.joystick) - - -def fuzz_joystick(joystick: wpilib.simulation.JoystickSim) -> None: - """Fuzz a Logitech Extreme 3D Pro flight stick.""" - for axis in range(5): - joystick.setRawAxis(axis, rand_axis()) - for button in range(12): - joystick.setRawButton(button, rand_bool()) - joystick.setPOV(rand_pov()) - - -def fuzz_xbox_gamepad(gamepad: wpilib.simulation.XboxControllerSim) -> None: - """Fuzz an XInput gamepad.""" - gamepad.setLeftX(rand_axis()) - gamepad.setLeftY(rand_axis()) - gamepad.setRightX(rand_axis()) - gamepad.setRightY(rand_axis()) - gamepad.setLeftTriggerAxis(random.random()) - gamepad.setRightTriggerAxis(random.random()) - for button in range(10): - gamepad.setRawButton(button, rand_bool()) - gamepad.setPOV(rand_pov()) - - -def get_alliance_stations() -> list[str]: - stations = (1, 2, 3) - if "CI" in os.environ: # pragma: no branch - return [ - f"{alliance}{station}" - for alliance in ("Blue", "Red") - for station in stations - ] - else: # pragma: no cover - return [f"Blue{random.choice(stations)}", f"Red{random.choice(stations)}"] - - -@pytest.mark.parametrize("station", get_alliance_stations()) -def test_fuzz(control: TestController, station: str) -> None: - station_id = getattr(hal.AllianceStationID, f"k{station}") - - with control.run_robot(): - things = AllTheThings() - hids = DSInputs() - - # Disabled mode - control.step_timing(seconds=0.2, autonomous=False, enabled=False) - DriverStationSim.setAllianceStationId(station_id) - things.fuzz() - hids.fuzz() - control.step_timing(seconds=0.2, autonomous=False, enabled=False) - - # Autonomous mode - things.fuzz() - control.step_timing(seconds=0.2, autonomous=True, enabled=False) - things.fuzz() - control.step_timing(seconds=0.2, autonomous=True, enabled=True) - - # Transition between autonomous and teleop - things.fuzz() - control.step_timing(seconds=0.2, autonomous=False, enabled=False) - things.fuzz() - control.step_timing(seconds=0.2, autonomous=False, enabled=True) - - # Teleop - for _ in range(20): - things.fuzz() - hids.fuzz() - control.step_timing(seconds=0.1, autonomous=False, enabled=True) - - DriverStationSim.setAllianceStationId(hal.AllianceStationID.kUnknown) - - -def test_fuzz_test(control: TestController) -> None: - with control.run_robot(): - hids = DSInputs() - - # Start the robot in disabled mode for a short period - control.step_timing(seconds=0.5, autonomous=False, enabled=False) - - DriverStationSim.setTest(True) - DriverStationSim.setEnabled(True) - - assert control.robot_is_alive - - for _ in range(20): - hids.fuzz() - DriverStationSim.notifyNewData() - wpilib.simulation.stepTiming(0.2) - assert control.robot_is_alive +from __future__ import annotations + +import os +import random +import typing + +import hal +import pytest +import wpilib.simulation +from wpilib.simulation import DriverStationSim + +if typing.TYPE_CHECKING: + from pyfrc.test_support.controller import TestController + +pytestmark = pytest.mark.integration_test + + +def rand_bool() -> bool: + return random.getrandbits(1) != 0 + + +def rand_axis() -> float: + """Get a random number between -1 and 1.""" + return random.random() * 2 - 1 + + +def rand_pov() -> int: + """Pick a random POV hat value.""" + return random.choice((-1, 0, 45, 90, 135, 180, 225, 270, 315)) + + +class AllTheThings: + """Fuzzer for robot hardware inputs.""" + + def __init__(self) -> None: + self.dios = [ + dio + for dio in map(wpilib.simulation.DIOSim, range(hal.getNumDigitalChannels())) + if dio.getInitialized() + ] + + def fuzz(self) -> None: + for dio in self.dios: + if dio.getIsInput(): # pragma: no branch + dio.setValue(rand_bool()) + + +class DSInputs: + """Fuzzer for HIDs attached to the driver station.""" + + def __init__(self) -> None: + self.gamepad = wpilib.simulation.XboxControllerSim(0) + self.joystick = wpilib.simulation.JoystickSim(1) + + def fuzz(self) -> None: + fuzz_xbox_gamepad(self.gamepad) + fuzz_joystick(self.joystick) + + +def fuzz_joystick(joystick: wpilib.simulation.JoystickSim) -> None: + """Fuzz a Logitech Extreme 3D Pro flight stick.""" + for axis in range(5): + joystick.setRawAxis(axis, rand_axis()) + for button in range(12): + joystick.setRawButton(button, rand_bool()) + joystick.setPOV(rand_pov()) + + +def fuzz_xbox_gamepad(gamepad: wpilib.simulation.XboxControllerSim) -> None: + """Fuzz an XInput gamepad.""" + gamepad.setLeftX(rand_axis()) + gamepad.setLeftY(rand_axis()) + gamepad.setRightX(rand_axis()) + gamepad.setRightY(rand_axis()) + gamepad.setLeftTriggerAxis(random.random()) + gamepad.setRightTriggerAxis(random.random()) + for button in range(10): + gamepad.setRawButton(button, rand_bool()) + gamepad.setPOV(rand_pov()) + + +def get_alliance_stations() -> list[str]: + stations = (1, 2, 3) + if "CI" in os.environ: # pragma: no branch + return [ + f"{alliance}{station}" + for alliance in ("Blue", "Red") + for station in stations + ] + else: # pragma: no cover + return [f"Blue{random.choice(stations)}", f"Red{random.choice(stations)}"] + + +@pytest.mark.parametrize("station", get_alliance_stations()) +def test_fuzz(control: TestController, station: str) -> None: + station_id = getattr(hal.AllianceStationID, f"k{station}") + + with control.run_robot(): + things = AllTheThings() + hids = DSInputs() + + # Disabled mode + control.step_timing(seconds=0.2, autonomous=False, enabled=False) + DriverStationSim.setAllianceStationId(station_id) + things.fuzz() + hids.fuzz() + control.step_timing(seconds=0.2, autonomous=False, enabled=False) + + # Autonomous mode + things.fuzz() + control.step_timing(seconds=0.2, autonomous=True, enabled=False) + things.fuzz() + control.step_timing(seconds=0.2, autonomous=True, enabled=True) + + # Transition between autonomous and teleop + things.fuzz() + control.step_timing(seconds=0.2, autonomous=False, enabled=False) + things.fuzz() + control.step_timing(seconds=0.2, autonomous=False, enabled=True) + + # Teleop + for _ in range(20): + things.fuzz() + hids.fuzz() + control.step_timing(seconds=0.1, autonomous=False, enabled=True) + + DriverStationSim.setAllianceStationId(hal.AllianceStationID.kUnknown) + + +def test_fuzz_test(control: TestController) -> None: + with control.run_robot(): + hids = DSInputs() + + # Start the robot in disabled mode for a short period + control.step_timing(seconds=0.5, autonomous=False, enabled=False) + + DriverStationSim.setTest(True) + DriverStationSim.setEnabled(True) + + assert control.robot_is_alive + + for _ in range(20): + hids.fuzz() + DriverStationSim.notifyNewData() + wpilib.simulation.stepTiming(0.2) + assert control.robot_is_alive diff --git a/tests/pyfrc_test.py b/tests/pyfrc_test.py index 6ffbcff9..7f07b4f2 100644 --- a/tests/pyfrc_test.py +++ b/tests/pyfrc_test.py @@ -1,11 +1,11 @@ -# NB: autonomous is tested separately in autonomous_test.py -from pyfrc.tests import ( - test_disabled, - test_operator_control, -) - -# Make pyflakes happy about our imports. -__all__ = ( - "test_disabled", - "test_operator_control", -) +# NB: autonomous is tested separately in autonomous_test.py +from pyfrc.tests import ( + test_disabled, + test_operator_control, +) + +# Make pyflakes happy about our imports. +__all__ = ( + "test_disabled", + "test_operator_control", +) diff --git a/tests/test_constrain_angle.py b/tests/test_constrain_angle.py index 57209a60..d51efb32 100644 --- a/tests/test_constrain_angle.py +++ b/tests/test_constrain_angle.py @@ -1,48 +1,48 @@ -import math - -import pytest -from hypothesis import given -from hypothesis.strategies import floats - -from utilities.functions import constrain_angle - - -@given(angle=floats(-math.pi, math.pi)) -def test_happy(angle: float): - """Test the happy path: the angle is in [-pi,pi].""" - assert constrain_angle(angle) == pytest.approx(angle) - - -@given(angle=floats(allow_infinity=False, allow_nan=False)) -def test_all(angle: float): - assert -math.pi <= constrain_angle(angle) <= math.pi - - -def test_zero(): - assert constrain_angle(0) == 0 - - -def test_edge_pos(): - assert constrain_angle(math.pi) == pytest.approx(math.pi) - - -def test_edge_neg(): - assert constrain_angle(-math.pi) == pytest.approx(-math.pi) - - -def test_revolution_pos(): - assert constrain_angle(math.tau) == pytest.approx(0) - - -def test_revolution_neg(): - assert constrain_angle(-math.tau) == pytest.approx(0) - - -@given(angle=floats(-math.tau, -math.pi, exclude_max=True)) -def test_one_wrap_positive_half(angle: float): - assert constrain_angle(angle) == pytest.approx(angle + math.tau) - - -@given(angle=floats(math.pi, math.tau, exclude_min=True)) -def test_one_wrap_negative_half(angle: float): - assert constrain_angle(angle) == pytest.approx(angle - math.tau) +import math + +import pytest +from hypothesis import given +from hypothesis.strategies import floats + +from utilities.functions import constrain_angle + + +@given(angle=floats(-math.pi, math.pi)) +def test_happy(angle: float): + """Test the happy path: the angle is in [-pi,pi].""" + assert constrain_angle(angle) == pytest.approx(angle) + + +@given(angle=floats(allow_infinity=False, allow_nan=False)) +def test_all(angle: float): + assert -math.pi <= constrain_angle(angle) <= math.pi + + +def test_zero(): + assert constrain_angle(0) == 0 + + +def test_edge_pos(): + assert constrain_angle(math.pi) == pytest.approx(math.pi) + + +def test_edge_neg(): + assert constrain_angle(-math.pi) == pytest.approx(-math.pi) + + +def test_revolution_pos(): + assert constrain_angle(math.tau) == pytest.approx(0) + + +def test_revolution_neg(): + assert constrain_angle(-math.tau) == pytest.approx(0) + + +@given(angle=floats(-math.tau, -math.pi, exclude_max=True)) +def test_one_wrap_positive_half(angle: float): + assert constrain_angle(angle) == pytest.approx(angle + math.tau) + + +@given(angle=floats(math.pi, math.tau, exclude_min=True)) +def test_one_wrap_negative_half(angle: float): + assert constrain_angle(angle) == pytest.approx(angle - math.tau) diff --git a/tests/test_functions.py b/tests/test_functions.py index 9e1c5ee3..88f76fb2 100644 --- a/tests/test_functions.py +++ b/tests/test_functions.py @@ -1,47 +1,47 @@ -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 -) - - -def test_rate_limit2d(): - assert rate_limit_2d((0, 0), (1, 0), rate_limit=0.5, dt=1) == (0.5, 0) - assert rate_limit_2d((0, 0), (1, 0), rate_limit=2, dt=1) == (1, 0) - assert rate_limit_2d((0, 0), (1, 1), rate_limit=0, dt=1) == (0, 0) - assert rate_limit_2d((0, 0), (1, 1), rate_limit=1, dt=0) == (0, 0) - - -@given( - cur=tuples(sensible_floats, sensible_floats), - target=tuples(sensible_floats, sensible_floats), - rate_limit=sensible_positive_floats, - dt=sensible_positive_floats, -) -def test_rate_limit_2d_limit(cur, target, rate_limit, dt): - new = rate_limit_2d(cur, target, rate_limit, dt) - diff = new[0] - cur[0], new[1] - cur[1] - assert hypot(*diff) <= rate_limit * dt or hypot(*diff) == approx(rate_limit * dt) - - -@given(mag=floats(0, 1), angle=sensible_floats) -def test_clamp2d_noconstrain(mag, angle): - # generate a point in the unit circle - x = cos(angle) * mag - y = sin(angle) * mag - # make sure its not contrained - assert clamp_2d((x, y), 1) == approx((x, y)) - - -@given(x=sensible_floats, y=sensible_floats) -def test_clamp2d_constrain(x, y): - result = clamp_2d((x, y), 1) - magnitude = hypot(*result) - assert magnitude <= 1 or magnitude == approx(1) +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 +) + + +def test_rate_limit2d(): + assert rate_limit_2d((0, 0), (1, 0), rate_limit=0.5, dt=1) == (0.5, 0) + assert rate_limit_2d((0, 0), (1, 0), rate_limit=2, dt=1) == (1, 0) + assert rate_limit_2d((0, 0), (1, 1), rate_limit=0, dt=1) == (0, 0) + assert rate_limit_2d((0, 0), (1, 1), rate_limit=1, dt=0) == (0, 0) + + +@given( + cur=tuples(sensible_floats, sensible_floats), + target=tuples(sensible_floats, sensible_floats), + rate_limit=sensible_positive_floats, + dt=sensible_positive_floats, +) +def test_rate_limit_2d_limit(cur, target, rate_limit, dt): + new = rate_limit_2d(cur, target, rate_limit, dt) + diff = new[0] - cur[0], new[1] - cur[1] + assert hypot(*diff) <= rate_limit * dt or hypot(*diff) == approx(rate_limit * dt) + + +@given(mag=floats(0, 1), angle=sensible_floats) +def test_clamp2d_noconstrain(mag, angle): + # generate a point in the unit circle + x = cos(angle) * mag + y = sin(angle) * mag + # make sure its not contrained + assert clamp_2d((x, y), 1) == approx((x, y)) + + +@given(x=sensible_floats, y=sensible_floats) +def test_clamp2d_constrain(x, y): + result = clamp_2d((x, y), 1) + magnitude = hypot(*result) + assert magnitude <= 1 or magnitude == approx(1) diff --git a/tests/test_scalers.py b/tests/test_scalers.py index f709a2c1..4009eef2 100644 --- a/tests/test_scalers.py +++ b/tests/test_scalers.py @@ -1,63 +1,63 @@ -import math - -from hypothesis import assume, given -from hypothesis.strategies import floats, tuples -from pytest import approx - -from utilities.scalers import apply_deadzone, map_exponential, scale_value - - -@given(value=floats(0, 1), threshold=floats(0, 1, exclude_min=True, exclude_max=True)) -def test_deadzone(value, threshold): - result = apply_deadzone(value, threshold) - neg_result = apply_deadzone(-value, threshold) - if value in (0, 1): - assert result == value - elif math.isclose(value, 0, abs_tol=threshold): - assert result == 0 - else: - assert 0 <= result <= value - assert neg_result == -result - - -@given(value=floats(0, 1)) -def test_deadzone_zero_threshold(value): - result = apply_deadzone(value, 0) - neg_result = apply_deadzone(-value, 0) - assert result == value - assert neg_result == -value - - -@given( - value=floats(0, 1), base=floats(1, exclude_min=True, allow_infinity=False, width=16) -) -def test_exponential(value, base): - result = map_exponential(value, base) - neg_result = map_exponential(-value, base) - if value in (0, 1): - assert result == value - else: - assert 0 <= result <= value or result == approx(value) - assert neg_result == -result - - -real_halves = floats(allow_nan=False, allow_infinity=False, width=16) - - -@given( - value=real_halves, - input_range=tuples(real_halves, real_halves).filter(lambda x: x[0] != x[1]), - output_range=tuples(real_halves, real_halves).filter(lambda x: x[0] != x[1]), -) -def test_scale_value( - value: float, input_range: tuple[float, float], output_range: tuple[float, float] -): - input_lower, input_upper = input_range - output_lower, output_upper = output_range - assume(min(input_lower, input_upper) <= value <= max(input_lower, input_upper)) - result = scale_value(value, input_lower, input_upper, output_lower, output_upper) - assert min(output_range) <= result <= max(output_range) - if value == input_lower: - assert result == output_lower - elif value == input_upper: - assert result == output_upper +import math + +from hypothesis import assume, given +from hypothesis.strategies import floats, tuples +from pytest import approx + +from utilities.scalers import apply_deadzone, map_exponential, scale_value + + +@given(value=floats(0, 1), threshold=floats(0, 1, exclude_min=True, exclude_max=True)) +def test_deadzone(value, threshold): + result = apply_deadzone(value, threshold) + neg_result = apply_deadzone(-value, threshold) + if value in (0, 1): + assert result == value + elif math.isclose(value, 0, abs_tol=threshold): + assert result == 0 + else: + assert 0 <= result <= value + assert neg_result == -result + + +@given(value=floats(0, 1)) +def test_deadzone_zero_threshold(value): + result = apply_deadzone(value, 0) + neg_result = apply_deadzone(-value, 0) + assert result == value + assert neg_result == -value + + +@given( + value=floats(0, 1), base=floats(1, exclude_min=True, allow_infinity=False, width=16) +) +def test_exponential(value, base): + result = map_exponential(value, base) + neg_result = map_exponential(-value, base) + if value in (0, 1): + assert result == value + else: + assert 0 <= result <= value or result == approx(value) + assert neg_result == -result + + +real_halves = floats(allow_nan=False, allow_infinity=False, width=16) + + +@given( + value=real_halves, + input_range=tuples(real_halves, real_halves).filter(lambda x: x[0] != x[1]), + output_range=tuples(real_halves, real_halves).filter(lambda x: x[0] != x[1]), +) +def test_scale_value( + value: float, input_range: tuple[float, float], output_range: tuple[float, float] +): + input_lower, input_upper = input_range + output_lower, output_upper = output_range + assume(min(input_lower, input_upper) <= value <= max(input_lower, input_upper)) + result = scale_value(value, input_lower, input_upper, output_lower, output_upper) + assert min(output_range) <= result <= max(output_range) + if value == input_lower: + assert result == output_lower + elif value == input_upper: + assert result == output_upper diff --git a/utilities/ctre.py b/utilities/ctre.py index 231f9585..b09c1264 100644 --- a/utilities/ctre.py +++ b/utilities/ctre.py @@ -1,6 +1,6 @@ -# Counts per revolution for the Falcon 500 integrated sensor. -FALCON_CPR = 2048 -# Freespeed in rev/s -FALCON_FREE_RPS = 100 - -VERSA_ENCODER_CPR = 4096 +# Counts per revolution for the Falcon 500 integrated sensor. +FALCON_CPR = 2048 +# Freespeed in rev/s +FALCON_FREE_RPS = 100 + +VERSA_ENCODER_CPR = 4096 diff --git a/utilities/functions.py b/utilities/functions.py index 3e5b440c..dbb876dc 100644 --- a/utilities/functions.py +++ b/utilities/functions.py @@ -1,62 +1,62 @@ -import math - -from wpimath.geometry import Rotation2d -from wpimath.kinematics import SwerveModuleState - - -def constrain_angle(angle: float) -> float: - """Wrap an angle to the interval [-pi,pi].""" - return math.atan2(math.sin(angle), math.cos(angle)) - - -def clamp(val: float, low: float, high: float) -> float: - return max(min(val, high), low) - - -def rate_limit_2d( - cur: tuple[float, float], target: tuple[float, float], rate_limit: float, dt: float -) -> tuple[float, float]: - """Limits the change in a vector to rate_limit * dt""" - err = (target[0] - cur[0], target[1] - cur[1]) - mag = math.hypot(*err) - if mag == 0: - return target - if mag < rate_limit * dt: - change = err - else: - err_norm = (err[0] / mag, err[1] / mag) - change = (err_norm[0] * rate_limit * dt, err_norm[1] * rate_limit * dt) - return cur[0] + change[0], cur[1] + change[1] - - -def rate_limit_module( - cur: SwerveModuleState, - target: SwerveModuleState, - rate_limit: float, - dt: float = 0.02, -) -> SwerveModuleState: - """ - Limit the change in a module state so that the acceleration dosent exceed rate_limit - """ - cur_vx = cur.angle.cos() * cur.speed - cur_vy = cur.angle.sin() * cur.speed - target_vx = target.angle.cos() * target.speed - target_vy = target.angle.sin() * target.speed - - new_vx, new_vy = rate_limit_2d( - (cur_vx, cur_vy), (target_vx, target_vy), rate_limit, dt - ) - new_speed = math.hypot(new_vx, new_vy) - rot = cur.angle if new_speed == 0 else Rotation2d(new_vx, new_vy) - return SwerveModuleState(new_speed, rot) - - -def clamp_2d(val: tuple[float, float], radius: float) -> tuple[float, float]: - """ - Constrains a vector to be within the unit circle - """ - mag = math.hypot(*val) - if mag == 0: - return (0, 0) - new_mag = min(mag, radius) - return new_mag * val[0] / mag, new_mag * val[1] / mag +import math + +from wpimath.geometry import Rotation2d +from wpimath.kinematics import SwerveModuleState + + +def constrain_angle(angle: float) -> float: + """Wrap an angle to the interval [-pi,pi].""" + return math.atan2(math.sin(angle), math.cos(angle)) + + +def clamp(val: float, low: float, high: float) -> float: + return max(min(val, high), low) + + +def rate_limit_2d( + cur: tuple[float, float], target: tuple[float, float], rate_limit: float, dt: float +) -> tuple[float, float]: + """Limits the change in a vector to rate_limit * dt""" + err = (target[0] - cur[0], target[1] - cur[1]) + mag = math.hypot(*err) + if mag == 0: + return target + if mag < rate_limit * dt: + change = err + else: + err_norm = (err[0] / mag, err[1] / mag) + change = (err_norm[0] * rate_limit * dt, err_norm[1] * rate_limit * dt) + return cur[0] + change[0], cur[1] + change[1] + + +def rate_limit_module( + cur: SwerveModuleState, + target: SwerveModuleState, + rate_limit: float, + dt: float = 0.02, +) -> SwerveModuleState: + """ + Limit the change in a module state so that the acceleration dosent exceed rate_limit + """ + cur_vx = cur.angle.cos() * cur.speed + cur_vy = cur.angle.sin() * cur.speed + target_vx = target.angle.cos() * target.speed + target_vy = target.angle.sin() * target.speed + + new_vx, new_vy = rate_limit_2d( + (cur_vx, cur_vy), (target_vx, target_vy), rate_limit, dt + ) + new_speed = math.hypot(new_vx, new_vy) + rot = cur.angle if new_speed == 0 else Rotation2d(new_vx, new_vy) + return SwerveModuleState(new_speed, rot) + + +def clamp_2d(val: tuple[float, float], radius: float) -> tuple[float, float]: + """ + Constrains a vector to be within the unit circle + """ + mag = math.hypot(*val) + if mag == 0: + return (0, 0) + new_mag = min(mag, radius) + return new_mag * val[0] / mag, new_mag * val[1] / mag diff --git a/utilities/game.py b/utilities/game.py index c22ea462..6ec55d3b 100644 --- a/utilities/game.py +++ b/utilities/game.py @@ -1,76 +1,76 @@ -"""Descriptions of the field and match state.""" - -import math - -import robotpy_apriltag -import wpilib -from wpimath.geometry import ( - Pose2d, - Rotation2d, - Translation2d, - Translation3d, -) - -apriltag_layout = robotpy_apriltag.AprilTagFieldLayout.loadField( - robotpy_apriltag.AprilTagField.k2025Reefscape -) - -APRILTAGS = apriltag_layout.getTags() - -L3_TAGS = [7, 9, 11, 18, 20, 22] -L2_TAGS = [6, 8, 10, 17, 19, 21] - -FIELD_WIDTH = apriltag_layout.getFieldWidth() -FIELD_LENGTH = apriltag_layout.getFieldLength() - - -# TODO: write functions for rotational symmetry - - -def field_flip_pose2d(p: Pose2d): - return Pose2d( - field_flip_translation2d(p.translation()), - field_flip_rotation2d(p.rotation()), - ) - - -def field_flip_translation3d(t: Translation3d): - return Translation3d(FIELD_LENGTH - t.x, t.y, t.z) - - -def field_flip_rotation2d(r: Rotation2d): - return Rotation2d(-r.cos(), r.sin()) - - -def field_flip_angle(r: float): - return math.atan2(math.sin(math.pi - r), math.cos(math.pi - r)) - - -def field_flip_translation2d(t: Translation2d): - return Translation2d(FIELD_LENGTH - t.x, t.y) - - -# This will default to the blue alliance if a proper link to the driver station has not yet been established -def is_red() -> bool: - return wpilib.DriverStation.getAlliance() == wpilib.DriverStation.Alliance.kRed - - -def nearest_reef_tag(pose: Pose2d) -> int: - distance = math.inf - closest_tag_id = 0 - - for tag_id in L2_TAGS + L3_TAGS: - tag_pose = apriltag_layout.getTagPose(tag_id) - - assert tag_pose - - robot_to_tag = tag_pose.toPose2d() - pose - if robot_to_tag.translation().norm() < distance: - distance = robot_to_tag.translation().norm() - closest_tag_id = tag_id - - return closest_tag_id - - -def is_L3(tag_id: int) -> bool: - return tag_id in L3_TAGS +"""Descriptions of the field and match state.""" + +import math + +import robotpy_apriltag +import wpilib +from wpimath.geometry import ( + Pose2d, + Rotation2d, + Translation2d, + Translation3d, +) + +apriltag_layout = robotpy_apriltag.AprilTagFieldLayout.loadField( + robotpy_apriltag.AprilTagField.k2025Reefscape +) + +APRILTAGS = apriltag_layout.getTags() + +L3_TAGS = [7, 9, 11, 18, 20, 22] +L2_TAGS = [6, 8, 10, 17, 19, 21] + +FIELD_WIDTH = apriltag_layout.getFieldWidth() +FIELD_LENGTH = apriltag_layout.getFieldLength() + + +# TODO: write functions for rotational symmetry + + +def field_flip_pose2d(p: Pose2d): + return Pose2d( + field_flip_translation2d(p.translation()), + field_flip_rotation2d(p.rotation()), + ) + + +def field_flip_translation3d(t: Translation3d): + return Translation3d(FIELD_LENGTH - t.x, t.y, t.z) + + +def field_flip_rotation2d(r: Rotation2d): + return Rotation2d(-r.cos(), r.sin()) + + +def field_flip_angle(r: float): + return math.atan2(math.sin(math.pi - r), math.cos(math.pi - r)) + + +def field_flip_translation2d(t: Translation2d): + return Translation2d(FIELD_LENGTH - t.x, t.y) + + +# This will default to the blue alliance if a proper link to the driver station has not yet been established +def is_red() -> bool: + return wpilib.DriverStation.getAlliance() == wpilib.DriverStation.Alliance.kRed + + +def nearest_reef_tag(pose: Pose2d) -> int: + distance = math.inf + closest_tag_id = 0 + + for tag_id in L2_TAGS + L3_TAGS: + tag_pose = apriltag_layout.getTagPose(tag_id) + + assert tag_pose + + robot_to_tag = tag_pose.toPose2d() - pose + if robot_to_tag.translation().norm() < distance: + distance = robot_to_tag.translation().norm() + closest_tag_id = tag_id + + return closest_tag_id + + +def is_L3(tag_id: int) -> bool: + return tag_id in L3_TAGS diff --git a/utilities/scalers.py b/utilities/scalers.py index c4ae39b3..7ae5b1d9 100644 --- a/utilities/scalers.py +++ b/utilities/scalers.py @@ -1,52 +1,52 @@ -import math - - -def apply_deadzone(value: float, threshold: float) -> float: - """Apply a deadzone to a value in [-1,1]. - - This ensures that the rest of the input space maps to [-1,1]. - """ - assert 0 <= threshold < 1 - if abs(value) < threshold: - return 0 - return (value - math.copysign(threshold, value)) / (1 - threshold) - - -def map_exponential(value: float, base: float) -> float: - """Takes a value in [-1,1] and maps it to an exponential curve.""" - assert base > 1 - return math.copysign((base ** abs(value) - 1) / (base - 1), value) - - -def rescale_js(value: float, deadzone: float, exponential: float = 1.5) -> float: - """Rescale a joystick input, applying a deadzone and exponential. - - Args: - value: the joystick value, in the interval [-1, 1]. - deadzone: the deadzone to apply. - exponential: the strength of the exponential to apply - (i.e. how non-linear should the response be) - """ - return map_exponential(apply_deadzone(value, deadzone), exponential + 1) - - -def scale_value( - value: float, - input_lower: float, - input_upper: float, - output_lower: float, - output_upper: float, -) -> float: - """Scales a value based on the input range and output range. - For example, to scale a joystick throttle (1 to -1) to 0-1, we would: - scale_value(joystick.getThrottle(), 1, -1, 0, 1) - """ - input_distance = input_upper - input_lower - output_distance = output_upper - output_lower - ratio = (value - input_lower) / input_distance - result = ratio * output_distance + output_lower - return result - - -def lerp(value: float, lo: float, hi: float) -> float: - return value * (hi - lo) + lo +import math + + +def apply_deadzone(value: float, threshold: float) -> float: + """Apply a deadzone to a value in [-1,1]. + + This ensures that the rest of the input space maps to [-1,1]. + """ + assert 0 <= threshold < 1 + if abs(value) < threshold: + return 0 + return (value - math.copysign(threshold, value)) / (1 - threshold) + + +def map_exponential(value: float, base: float) -> float: + """Takes a value in [-1,1] and maps it to an exponential curve.""" + assert base > 1 + return math.copysign((base ** abs(value) - 1) / (base - 1), value) + + +def rescale_js(value: float, deadzone: float, exponential: float = 1.5) -> float: + """Rescale a joystick input, applying a deadzone and exponential. + + Args: + value: the joystick value, in the interval [-1, 1]. + deadzone: the deadzone to apply. + exponential: the strength of the exponential to apply + (i.e. how non-linear should the response be) + """ + return map_exponential(apply_deadzone(value, deadzone), exponential + 1) + + +def scale_value( + value: float, + input_lower: float, + input_upper: float, + output_lower: float, + output_upper: float, +) -> float: + """Scales a value based on the input range and output range. + For example, to scale a joystick throttle (1 to -1) to 0-1, we would: + scale_value(joystick.getThrottle(), 1, -1, 0, 1) + """ + input_distance = input_upper - input_lower + output_distance = output_upper - output_lower + ratio = (value - input_lower) / input_distance + result = ratio * output_distance + output_lower + return result + + +def lerp(value: float, lo: float, hi: float) -> float: + return value * (hi - lo) + lo