From f800b5345625cdc77954e053413453762b298ce4 Mon Sep 17 00:00:00 2001 From: Joao Mario Lago Date: Mon, 30 Sep 2024 08:19:41 -0300 Subject: [PATCH] core:autopilot_manager: Fix race setting router * Change to use stop and start since directlly changing the router without modifying should_be_running can cause multiple starts --- core/services/ardupilot_manager/mavlink_proxy/Manager.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/core/services/ardupilot_manager/mavlink_proxy/Manager.py b/core/services/ardupilot_manager/mavlink_proxy/Manager.py index 2d9a207f4b..eb0d978c65 100644 --- a/core/services/ardupilot_manager/mavlink_proxy/Manager.py +++ b/core/services/ardupilot_manager/mavlink_proxy/Manager.py @@ -124,12 +124,12 @@ async def set_preferred_router(self, router_name: str) -> None: try: endpoints = self.endpoints() master_endpoint = self.master_endpoint - await self.tool.exit() + await self.stop() self.tool = AbstractRouter.get_interface(router_name)() for endpoint in endpoints: self.tool.add_endpoint(endpoint) if master_endpoint: - await self.tool.start(master_endpoint) + await self.start(master_endpoint) except Exception as error: logger.error(f"Failed to set preferred router to {router_name}. {error}")