Skip to content

Commit

Permalink
Format
Browse files Browse the repository at this point in the history
  • Loading branch information
umroverPerception committed Mar 23, 2024
1 parent 4873738 commit 3aadb73
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 2 deletions.
2 changes: 1 addition & 1 deletion src/navigation/context.py
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,7 @@ def __init__(self, ctx: Context, min_hits: int = MIN_HITS, max_hits: int = MAX_H

def push_frame(self, tags: List[LongRangeTag]) -> None:
"""
Loops through our current list of our stored tags and checks if the new message includes each tag or doesn't.
Loops through our current list of our stored tags and checks if the new message includes each tag or doesn't.
If it does include it, we will increment our hit count for that tag id and reset the time we saw it.
If it does not include it, we will decrement our hit count for that tag id, and if the hit count becomes zero, then we remove it from our stored list.
If there are tag ids in the new message that we don't have stored, we will add it to our stored list.
Expand Down
4 changes: 3 additions & 1 deletion src/navigation/navigation.py
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,9 @@ def __init__(self, context: Context):
],
)
self.state_machine.add_transitions(ApproachObjectState(), [DoneState(), SearchState(), RecoveryState()])
self.state_machine.add_transitions(LongRangeState(), [ApproachPostState(), SearchState(), WaypointState(), RecoveryState()])
self.state_machine.add_transitions(
LongRangeState(), [ApproachPostState(), SearchState(), WaypointState(), RecoveryState()]
)
self.state_machine.add_transitions(OffState(), [WaypointState(), DoneState()])
self.state_machine.configure_off_switch(OffState(), off_check)
self.state_machine_server = StatePublisher(self.state_machine, "nav_structure", 1, "nav_state", 10)
Expand Down

0 comments on commit 3aadb73

Please sign in to comment.