Skip to content

Commit

Permalink
Redid the check for intended start pos!
Browse files Browse the repository at this point in the history
  • Loading branch information
Tsunami014 committed Mar 15, 2024
1 parent ec2665f commit 6af90d1
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 17 deletions.
22 changes: 14 additions & 8 deletions robot.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
from utilities.game import is_red
from utilities.scalers import rescale_js
from utilities.functions import clamp
from utilities.position import on_same_side_of_stage, y_close_to_stage
from utilities.position import distance_between


class MyRobot(magicbot.MagicRobot):
Expand All @@ -47,6 +47,8 @@ class MyRobot(magicbot.MagicRobot):
vision_port: VisualLocalizer
vision_starboard: VisualLocalizer

START_POS_TOLERANCE = 1

def createObjects(self) -> None:
self.data_log = wpilib.DataLogManager.getLog()

Expand All @@ -71,7 +73,7 @@ def createObjects(self) -> None:
)

def teleopInit(self) -> None:
pass
self.field.getObject("Intended start pos").setPoses([])

def teleopPeriodic(self) -> None:
if self.climber.should_lock_mechanisms():
Expand Down Expand Up @@ -204,6 +206,7 @@ def disabledPeriodic(self) -> None:
if (
not self.vision_port.sees_target()
and not self.vision_starboard.sees_target()
and not self.isSimulation()
):
self.status_lights.no_vision()
else:
Expand All @@ -213,11 +216,14 @@ def disabledPeriodic(self) -> None:
intended_start_pose = selected_auto.get_starting_pose()
current_pose = self.chassis.get_pose()
if intended_start_pose is not None:
if on_same_side_of_stage(intended_start_pose, current_pose):
if y_close_to_stage(current_pose):
self.status_lights.too_close_to_stage()
else:
self.status_lights.rainbow()
self.field.getObject("Intended start pos").setPose(
intended_start_pose
)
if (
distance_between(intended_start_pose, current_pose)
< self.START_POS_TOLERANCE
):
self.status_lights.rainbow()
else:
self.status_lights.invalid_start()
else:
Expand All @@ -226,7 +232,7 @@ def disabledPeriodic(self) -> None:
self.status_lights.missing_start_pose()

def autonomousInit(self) -> None:
pass
self.field.getObject("Intended start pos").setPoses([])


if __name__ == "__main__":
Expand Down
11 changes: 2 additions & 9 deletions utilities/position.py
Original file line number Diff line number Diff line change
Expand Up @@ -76,15 +76,8 @@ class TeamPoses:
RED_PODIUM = field_flip_pose2d(BLUE_PODIUM)


def on_same_side_of_stage(intended_start_pose: Pose2d, current_pose: Pose2d) -> bool:
return not (
(intended_start_pose.y > TeamPoses.BLUE_PODIUM.y)
^ (current_pose.y > TeamPoses.BLUE_PODIUM.y)
)


def y_close_to_stage(pose: Pose2d) -> bool:
return abs(pose.y - TeamPoses.BLUE_PODIUM.y) < 0.9
def distance_between(intended_start_pose: Pose2d, current_pose: Pose2d) -> float:
return (intended_start_pose.translation() - current_pose.translation()).norm()


class PathPositions:
Expand Down

0 comments on commit 6af90d1

Please sign in to comment.