Skip to content

Commit

Permalink
Update sim start positions
Browse files Browse the repository at this point in the history
  • Loading branch information
mlists committed Mar 14, 2024
1 parent 614a8f4 commit 10018a1
Showing 1 changed file with 11 additions and 7 deletions.
18 changes: 11 additions & 7 deletions autonomous/autonomous.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
Path,
ShootingPositions,
PathPositions,
TeamPoses,
)
from utilities import game
from autonomous.base import AutoBase
Expand All @@ -16,7 +17,7 @@ def rotation_to_red_speaker(position: Translation2d) -> Rotation2d:
return t.angle() + Rotation2d(math.pi)


class PodiumSpeakerAmpTopcentre(AutoBase):
class PodiumSpeakerAmpCentre1(AutoBase):
MODE_NAME = "5 notes: podium, speaker, amp, centre 1"

def __init__(self) -> None:
Expand Down Expand Up @@ -50,9 +51,10 @@ def __init__(self) -> None:
Path([NotePositions.amp], face_target=True),
]
# Start pose only needs to be on the correct half of the field,
# so choose the podium as a reference point
# so choose the subwoofer
start_pose = Pose2d(
NotePositions.podium, rotation_to_red_speaker(NotePositions.podium)
TeamPoses.RED_TEST_POSE.translation(),
rotation_to_red_speaker(TeamPoses.RED_TEST_POSE.translation()),
)
super().__init__(note_paths, shoot_paths, start_pose)

Expand All @@ -71,9 +73,10 @@ def __init__(self) -> None:
Path([PathPositions.avoid_wall, NotePositions.amp], face_target=True),
]
# Start pose only needs to be on the correct half of the field,
# so choose the amp as a reference point
# so choose the subwoofer
start_pose = Pose2d(
NotePositions.amp, rotation_to_red_speaker(NotePositions.amp)
TeamPoses.RED_TEST_POSE.translation(),
rotation_to_red_speaker(TeamPoses.RED_TEST_POSE.translation()),
)
super().__init__(note_paths, shoot_paths, start_pose)

Expand All @@ -98,9 +101,10 @@ def __init__(self) -> None:
),
]
# Start pose only needs to be on the correct half of the field,
# so choose the speaker as a reference point
# so choose the subwoofer
start_pose = Pose2d(
NotePositions.speaker, rotation_to_red_speaker(NotePositions.speaker)
TeamPoses.RED_TEST_POSE.translation(),
rotation_to_red_speaker(TeamPoses.RED_TEST_POSE.translation()),
)
super().__init__(note_paths, shoot_paths, start_pose)

Expand Down

0 comments on commit 10018a1

Please sign in to comment.