Skip to content

Commit 0f150cc

Browse files
committed
feat(FC connection): If no FC is detected on the serial ports, try the network ports.
fix #728
1 parent 39a0add commit 0f150cc

1 file changed

Lines changed: 70 additions & 26 deletions

File tree

ardupilot_methodic_configurator/backend_flightcontroller.py

Lines changed: 70 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -122,6 +122,30 @@ def add_connection(self, connection_string: str) -> bool:
122122
logging_debug(_("Did not add empty connection"))
123123
return False
124124

125+
def _register_and_try_connect(
126+
self,
127+
comport: mavutil.SerialPort,
128+
progress_callback: Union[None, Callable[[int, int], None]],
129+
baudrate: int,
130+
log_errors: bool,
131+
) -> str:
132+
"""
133+
Register a device in the connection list (if missing) and attempt connection.
134+
135+
Returns:
136+
str: empty string on success, or error message.
137+
138+
"""
139+
# set comport for subsequent calls
140+
self.comport = comport
141+
# Add the detected port to the list of available connections if it is not there
142+
if self.comport and self.comport.device not in [t[0] for t in self.__connection_tuples]:
143+
self.__connection_tuples.insert(-1, (self.comport.device, getattr(self.comport, "description", "")))
144+
# Try to connect
145+
return self.__create_connection_with_retry(
146+
progress_callback=progress_callback, baudrate=baudrate, log_errors=log_errors
147+
)
148+
125149
def connect(
126150
self, device: str, progress_callback: Union[None, Callable[[int, int], None]] = None, log_errors: bool = True
127151
) -> str:
@@ -130,7 +154,8 @@ def connect(
130154
131155
This method attempts to connect to the FlightController using the provided device
132156
connection string. If no device is specified, it attempts to auto-detect a serial
133-
port that matches the preferred ports list. If a device is specified as 'test',
157+
port that matches the preferred ports list. If no serial device is found it tries
158+
the "standard" ArduPilot UDP and TCP connections. If a device is specified as 'test',
134159
it sets some test parameters for debugging purposes.
135160
136161
Args:
@@ -150,31 +175,50 @@ def connect(
150175
return ""
151176
self.add_connection(device)
152177
self.comport = mavutil.SerialPort(device=device, description=device)
153-
else:
154-
autodetect_serial = self.__auto_detect_serial()
155-
if autodetect_serial:
156-
# Resolve the soft link if it's a Linux system
157-
if os_name == "posix":
158-
try:
159-
dev = autodetect_serial[0].device
160-
logging_debug(_("Auto-detected device %s"), dev)
161-
# Get the directory part of the soft link
162-
softlink_dir = os_path.dirname(dev)
163-
# Resolve the soft link and join it with the directory part
164-
resolved_path = os_path.abspath(os_path.join(softlink_dir, os_readlink(dev)))
165-
autodetect_serial[0].device = resolved_path
166-
logging_debug(_("Resolved soft link %s to %s"), dev, resolved_path)
167-
except OSError:
168-
pass # Not a soft link, proceed with the original device path
169-
self.comport = autodetect_serial[0]
170-
# Add the detected serial port to the list of available connections if it is not there
171-
if self.comport and self.comport.device not in [t[0] for t in self.__connection_tuples]:
172-
self.__connection_tuples.insert(-1, (self.comport.device, getattr(self.comport, "description", "")))
173-
else:
174-
return _("No serial ports found. Please connect a flight controller and try again.")
175-
return self.__create_connection_with_retry(
176-
progress_callback=progress_callback, baudrate=self.__baudrate, log_errors=log_errors
177-
)
178+
return self.__create_connection_with_retry(
179+
progress_callback=progress_callback, baudrate=self.__baudrate, log_errors=log_errors
180+
)
181+
182+
# Try to autodetect serial ports
183+
autodetect_serial = self.__auto_detect_serial()
184+
if autodetect_serial:
185+
# Resolve the soft link if it's a Linux system
186+
if os_name == "posix":
187+
try:
188+
dev = autodetect_serial[0].device
189+
logging_debug(_("Auto-detected device %s"), dev)
190+
# Get the directory part of the soft link
191+
softlink_dir = os_path.dirname(dev)
192+
# Resolve the soft link and join it with the directory part
193+
resolved_path = os_path.abspath(os_path.join(softlink_dir, os_readlink(dev)))
194+
autodetect_serial[0].device = resolved_path
195+
logging_debug(_("Resolved soft link %s to %s"), dev, resolved_path)
196+
except OSError:
197+
pass # Not a soft link, proceed with the original device path
198+
err = self._register_and_try_connect(
199+
comport=autodetect_serial[0],
200+
progress_callback=progress_callback,
201+
baudrate=self.__baudrate,
202+
log_errors=False,
203+
)
204+
if err == "":
205+
return ""
206+
207+
# Try to autodetect network ports
208+
netports = FlightController.__list_network_ports()
209+
for port in netports:
210+
# try to connect to each "standard" ArduPilot UDP and TCP ports
211+
logging_debug(_("Trying network port %s"), port)
212+
err = self._register_and_try_connect(
213+
comport=mavutil.SerialPort(device=port, description=port),
214+
progress_callback=progress_callback,
215+
baudrate=self.__baudrate,
216+
log_errors=False,
217+
)
218+
if err == "":
219+
return ""
220+
221+
return _("No auto-detected ports responded. Please connect a flight controller and try again.")
178222

179223
def __request_banner(self) -> None:
180224
"""Request banner information from the flight controller."""

0 commit comments

Comments
 (0)