@@ -472,7 +472,7 @@ def printer(context, msg):
472472 self .__logger .error (msg .format (context .locals .process_name ))
473473
474474 # Setup a timer to send us a SIGTERM if we don't shutdown quickly.
475- sigterm_timeout = cast ( float , self .__sigterm_timeout_value )
475+ sigterm_timeout = self .__sigterm_timeout_value
476476 self .__sigterm_timer = TimerAction (
477477 period = sigterm_timeout ,
478478 actions = [
@@ -488,7 +488,7 @@ def printer(context, msg):
488488 ],
489489 cancel_on_shutdown = False ,
490490 )
491- sigkill_timeout = sigterm_timeout + cast ( float , self .__sigkill_timeout_value )
491+ sigkill_timeout = sigterm_timeout + self .__sigkill_timeout_value
492492 # Setup a timer to send us a SIGKILL if we don't shutdown after SIGTERM.
493493 self .__sigkill_timer = TimerAction (
494494 period = sigkill_timeout ,
@@ -772,12 +772,15 @@ def execute(self, context: LaunchContext) -> None:
772772 ]
773773 for event_handler in event_handlers :
774774 context .register_event_handler (event_handler )
775- self .__sigterm_timeout_value = perform_typed_substitution (
776- context , self .__sigterm_timeout , float )
777- self .__sigkill_timeout_value = perform_typed_substitution (
778- context , self .__sigkill_timeout , float )
775+ self .__sigterm_timeout_value = cast (
776+ float , perform_typed_substitution (context , self .__sigterm_timeout , float )
777+ )
778+ self .__sigkill_timeout_value = cast (
779+ float , perform_typed_substitution (context , self .__sigkill_timeout , float )
780+ )
779781 self .__signal_lingering_subprocesses_value = perform_typed_substitution (
780- context , self .__signal_lingering_subprocesses , bool )
782+ context , self .__signal_lingering_subprocesses , bool
783+ )
781784
782785 try :
783786 self .__completed_future = context .asyncio_loop .create_future ()
0 commit comments