77from typing import Any , List , Optional , Set
88
99import psutil
10+ from commonwealth .mavlink_comm .typedefs import MavlinkFirmwareType
1011from commonwealth .mavlink_comm .VehicleManager import VehicleManager
1112from commonwealth .utils .Singleton import Singleton
1213from elftools .elf .elffile import ELFFile
@@ -151,6 +152,7 @@ async def setup(self) -> None:
151152 self .vehicle_manager = VehicleManager ()
152153 self ._heartbeat_fail_count = 0 # Consecutive heartbeat failures
153154 self ._max_heartbeat_failures = 10 # Threshold for restarting Ardupilot after consecutive heartbeat failures
155+ self ._firmware_vehicle_type : Optional [MavlinkFirmwareType ] = None
154156
155157 self .should_be_running = False
156158 self .remove_old_logs ()
@@ -203,7 +205,7 @@ async def auto_restart_ardupilot(self) -> None:
203205 except Exception as error :
204206 logger .warning (f"Could not start Ardupilot: { error } " )
205207
206- # Monitor MAVLink heartbeat while autopilot is supposed to be running
208+ # Monitor MAVLink heartbeat and restart only for ROVs (Sub)
207209 if self .should_be_running and self .is_running ():
208210 try :
209211 alive = await self .vehicle_manager .is_heart_beating ()
@@ -223,7 +225,14 @@ async def auto_restart_ardupilot(self) -> None:
223225 if self ._heartbeat_fail_count >= self ._max_heartbeat_failures :
224226 logger .warning ("Consecutive heartbeat failures threshold reached — restarting Ardupilot." )
225227 try :
226- await self .restart_ardupilot ()
228+ if self ._firmware_vehicle_type is None :
229+ try :
230+ vehicle_type = await self .vehicle_manager .get_vehicle_type ()
231+ self ._firmware_vehicle_type = vehicle_type .mavlink_firmware_type ()
232+ except Exception :
233+ pass
234+ if self ._firmware_vehicle_type == MavlinkFirmwareType .ArduSub :
235+ await self .restart_ardupilot ()
227236 except Exception as error :
228237 logger .warning (f"Failed to restart Ardupilot after heartbeat failures: { error } " )
229238 self ._heartbeat_fail_count = 0
0 commit comments