Skip to content

Commit ca9edd1

Browse files
Williangalvanipatrickelectric
authored andcommitted
ardupilot_manager: allow updating master endpoint
1 parent 69fd303 commit ca9edd1

File tree

3 files changed

+12
-2
lines changed

3 files changed

+12
-2
lines changed

core/services/ardupilot_manager/autopilot_manager.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -674,7 +674,7 @@ async def restore_default_firmware(self, board: FlightController) -> None:
674674
async def set_manual_board_master_endpoint(self, endpoint: Endpoint) -> bool:
675675
self.configuration["manual_board_master_endpoint"] = endpoint.as_dict()
676676
self.settings.save(self.configuration)
677-
self._save_current_endpoints()
677+
self.mavlink_manager.master_endpoint = endpoint
678678
await self.mavlink_manager.restart()
679679
return True
680680

core/services/ardupilot_manager/mavlink_proxy/AbstractRouter.py

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -94,6 +94,10 @@ def version(self) -> Optional[str]:
9494
def master_endpoint(self) -> Optional[Endpoint]:
9595
return self._master_endpoint
9696

97+
@master_endpoint.setter
98+
def master_endpoint(self, master_endpoint: Endpoint) -> None:
99+
self._master_endpoint = master_endpoint
100+
97101
async def start(self, master_endpoint: Endpoint) -> None:
98102
self._master_endpoint = master_endpoint
99103
command = self.assemble_command(self._master_endpoint)

core/services/ardupilot_manager/mavlink_proxy/Manager.py

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -114,6 +114,10 @@ def _reset_endpoints(self) -> None:
114114
def master_endpoint(self) -> Optional[Endpoint]:
115115
return self.tool.master_endpoint
116116

117+
@master_endpoint.setter
118+
def master_endpoint(self, master_endpoint: Endpoint) -> None:
119+
self.tool.master_endpoint = master_endpoint
120+
117121
async def start(self, master_endpoint: Endpoint) -> None:
118122
# If the tool is already running, don't start it again to avoid port conflicts
119123
if self.should_be_running and await self.is_running():
@@ -151,8 +155,10 @@ async def stop(self) -> None:
151155
self.should_be_running = False
152156
await self.tool.exit()
153157

154-
async def restart(self) -> None:
158+
async def restart(self, master_endpoint: Optional[Endpoint] = None) -> None:
155159
self.should_be_running = False
160+
if master_endpoint:
161+
self.tool.master_endpoint = master_endpoint
156162
await self.tool.restart()
157163
self._last_valid_endpoints = self.endpoints()
158164
self.should_be_running = True

0 commit comments

Comments
 (0)