@@ -228,28 +228,33 @@ static void WebUpdateSendNetworks(AsyncWebServerRequest *request)
228228 }
229229}
230230
231- static void sendResponse (AsyncWebServerRequest *request, const String &msg, WiFiMode_t mode ) {
232- AsyncWebServerResponse *response = request->beginResponse (200 , " text/plain " , msg);
231+ static void sendResponse (AsyncWebServerRequest *request, const String &msg, const String &type = " text/plain " ) {
232+ AsyncWebServerResponse *response = request->beginResponse (200 , type , msg);
233233 response->addHeader (" Connection" , " close" );
234234 request->send (response);
235235 request->client ()->close ();
236236 changeTime = millis ();
237+ }
238+
239+ static void changeWifiMode (WiFiMode_t mode){
237240 changeMode = mode;
238241}
239242
240243static void WebUpdateAccessPoint (AsyncWebServerRequest *request)
241244{
242245 DBGLN (" Starting Access Point" );
243246 String msg = String (" Access Point starting, please connect to access point '" ) + wifi_ap_ssid + " ' with password '" + wifi_ap_password + " '" ;
244- sendResponse (request, msg, WIFI_AP);
247+ sendResponse (request, msg);
248+ changeWifiMode (WIFI_AP);
245249}
246250
247251static void WebUpdateConnect (AsyncWebServerRequest *request)
248252{
249253 DBGLN (" Connecting to home network" );
250254 String msg = String (" Connecting to network '" ) + station_ssid + " ', connect to http://" +
251255 myHostname + " .local from a browser on that network" ;
252- sendResponse (request, msg, WIFI_STA);
256+ sendResponse (request, msg);
257+ changeWifiMode (WIFI_STA);
253258}
254259
255260static void WebUpdateSetHome (AsyncWebServerRequest *request)
@@ -280,13 +285,16 @@ static void WebUpdateForget(AsyncWebServerRequest *request)
280285 strcpy (station_ssid, firmwareOptions.home_wifi_ssid );
281286 strcpy (station_password, firmwareOptions.home_wifi_password );
282287 String msg = String (" Temporary network forgotten, attempting to connect to network '" ) + station_ssid + " '" ;
283- sendResponse (request, msg, WIFI_STA);
288+ sendResponse (request, msg);
289+ changeWifiMode (WIFI_STA);
290+
284291 }
285292 else {
286293 station_ssid[0 ] = 0 ;
287294 station_password[0 ] = 0 ;
288295 String msg = String (" Home network forgotten, please connect to access point '" ) + wifi_ap_ssid + " ' with password '" + wifi_ap_password + " '" ;
289- sendResponse (request, msg, WIFI_AP);
296+ sendResponse (request, msg);
297+ changeWifiMode (WIFI_AP);
290298 }
291299}
292300
@@ -465,8 +473,8 @@ static void WebMAVLinkHandler(AsyncWebServerRequest *request)
465473 json[" counters" ][" packets_up" ] = stats->packets_uplink ;
466474 json[" counters" ][" drops_down" ] = stats->drops_downlink ;
467475 json[" counters" ][" overflows_down" ] = stats->overflows_downlink ;
468- json[" ports" ][" listen" ] = MAVLINK_PORT_LISTEN ;
469- json[" ports" ][" send" ] = MAVLINK_PORT_SEND ;
476+ json[" ports" ][" listen" ] = config. GetMavlinkListenPort () ;
477+ json[" ports" ][" send" ] = config. GetMavlinkSendPort () ;
470478 if (gcsIPSet) {
471479 json[" ip" ][" gcs" ] = gcsIP.toString ();
472480 } else {
@@ -478,6 +486,35 @@ static void WebMAVLinkHandler(AsyncWebServerRequest *request)
478486 serializeJson (json, *response);
479487 request->send (response);
480488}
489+
490+ static void WebUpdateSetMavLink (AsyncWebServerRequest *request)
491+ {
492+ uint16_t listen_port = request->arg (" listen" ).toInt ();
493+ uint16_t send_port = request->arg (" send" ).toInt ();
494+
495+ DBGLN (" Setting MavLink configuration: listen=%d, send=%d" , listen_port, send_port);
496+
497+ config.SetMavlinkListenPort (listen_port);
498+ config.SetMavlinkSendPort (send_port);
499+ config.SetWiFiService (WIFI_SERVICE_MAVLINK_TX);
500+ config.Commit ();
501+
502+ // Restart MavLink UDP service
503+ mavlinkUDP.stop ();
504+ mavlinkUDP.begin (config.GetMavlinkListenPort ());
505+
506+ String response = F (
507+ " <html><head>"
508+ " <meta http-equiv='refresh' content='2;url=/'>"
509+ " <title>MavLink Settings Updated</title>"
510+ " </head><body>"
511+ " <h1>MavLink Settings Updated Successfully</h1>"
512+ " <p>Redirecting back to the main page in 2 seconds...</p>"
513+ " </body></html>"
514+ );
515+
516+ sendResponse (request, response, " text/html" );
517+ }
481518#endif
482519
483520static void wifiOff ()
@@ -600,6 +637,9 @@ static void startServices()
600637 server.on (" /config" , HTTP_GET, GetConfiguration);
601638 server.on (" /networks.json" , WebUpdateSendNetworks);
602639 server.on (" /sethome" , WebUpdateSetHome);
640+ #if defined(MAVLINK_ENABLED)
641+ server.on (" /setmavlink" , WebUpdateSetMavLink);
642+ #endif
603643 server.on (" /forget" , WebUpdateForget);
604644 server.on (" /connect" , WebUpdateConnect);
605645 server.on (" /access" , WebUpdateAccessPoint);
@@ -632,7 +672,7 @@ static void startServices()
632672
633673 startMDNS ();
634674#if defined(MAVLINK_ENABLED)
635- mavlinkUDP.begin (MAVLINK_PORT_LISTEN );
675+ mavlinkUDP.begin (config. GetMavlinkListenPort () );
636676#endif
637677
638678 servicesStarted = true ;
@@ -748,7 +788,7 @@ static void HandleWebUpdate()
748788 remote = WiFi.broadcastIP ();
749789 }
750790
751- mavlinkUDP.beginPacket (remote, MAVLINK_PORT_SEND );
791+ mavlinkUDP.beginPacket (remote, config. GetMavlinkSendPort () );
752792 mavlink_message_t * msgQueue = mavlink.GetQueuedMsgs ();
753793 for (uint8_t i = 0 ; i < mavlink.GetQueuedMsgCount (); i++)
754794 {
0 commit comments