Skip to content

Commit

Permalink
chore: allow empty KinematicCondition
Browse files Browse the repository at this point in the history
  • Loading branch information
hayato-m126 committed Jul 18, 2024
1 parent 120e57a commit d189dcf
Showing 1 changed file with 6 additions and 6 deletions.
12 changes: 6 additions & 6 deletions log_evaluator/log_evaluator/planning_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -100,9 +100,9 @@ def is_ended(self, lane_info_tuple: tuple[float, float, float]) -> bool:


class KinematicCondition(BaseModel):
vel: MinMax
acc: MinMax
jerk: MinMax
vel: MinMax | None = None
acc: MinMax | None = None
jerk: MinMax | None = None

@classmethod
def diag_kinematic_state(cls, kinematic_state: DiagnosticStatus) -> tuple[float, float, float]:
Expand All @@ -119,11 +119,11 @@ def diag_kinematic_state(cls, kinematic_state: DiagnosticStatus) -> tuple[float,

def match_condition(self, kinematic_state_tuple: tuple[float, float, float]) -> bool:
vel, acc, jerk = kinematic_state_tuple
if not self.vel.min <= vel <= self.vel.max:
if self.vel is not None and not self.vel.min <= vel <= self.vel.max:
return False
if not self.acc.min <= acc <= self.acc.max:
if self.acc is not None and not self.acc.min <= acc <= self.acc.max:
return False
if not self.jerk.min <= jerk <= self.jerk.max:
if self.jerk is not None and not self.jerk.min <= jerk <= self.jerk.max:
return False
return True

Expand Down

0 comments on commit d189dcf

Please sign in to comment.