@@ -294,28 +294,33 @@ static void WebUpdateSendNetworks(AsyncWebServerRequest *request)
294294 }
295295}
296296
297- static void sendResponse (AsyncWebServerRequest *request, const String &msg, WiFiMode_t mode ) {
298- AsyncWebServerResponse *response = request->beginResponse (200 , " text/plain " , msg);
297+ static void sendResponse (AsyncWebServerRequest *request, const String &msg, const String &type = " text/plain " ) {
298+ AsyncWebServerResponse *response = request->beginResponse (200 , type , msg);
299299 response->addHeader (" Connection" , " close" );
300300 request->send (response);
301301 request->client ()->close ();
302302 changeTime = millis ();
303+ }
304+
305+ static void changeWifiMode (WiFiMode_t mode){
303306 changeMode = mode;
304307}
305308
306309static void WebUpdateAccessPoint (AsyncWebServerRequest *request)
307310{
308311 DBGLN (" Starting Access Point" );
309312 String msg = String (" Access Point starting, please connect to access point '" ) + wifi_ap_ssid + " ' with password '" + wifi_ap_password + " '" ;
310- sendResponse (request, msg, WIFI_AP);
313+ sendResponse (request, msg);
314+ changeWifiMode (WIFI_AP);
311315}
312316
313317static void WebUpdateConnect (AsyncWebServerRequest *request)
314318{
315319 DBGLN (" Connecting to home network" );
316320 String msg = String (" Connecting to network '" ) + station_ssid + " ', connect to http://" +
317321 myHostname + " .local from a browser on that network" ;
318- sendResponse (request, msg, WIFI_STA);
322+ sendResponse (request, msg);
323+ changeWifiMode (WIFI_STA);
319324}
320325
321326static void WebUpdateSetHome (AsyncWebServerRequest *request)
@@ -346,13 +351,16 @@ static void WebUpdateForget(AsyncWebServerRequest *request)
346351 strcpy (station_ssid, firmwareOptions.home_wifi_ssid );
347352 strcpy (station_password, firmwareOptions.home_wifi_password );
348353 String msg = String (" Temporary network forgotten, attempting to connect to network '" ) + station_ssid + " '" ;
349- sendResponse (request, msg, WIFI_STA);
354+ sendResponse (request, msg);
355+ changeWifiMode (WIFI_STA);
356+
350357 }
351358 else {
352359 station_ssid[0 ] = 0 ;
353360 station_password[0 ] = 0 ;
354361 String msg = String (" Home network forgotten, please connect to access point '" ) + wifi_ap_ssid + " ' with password '" + wifi_ap_password + " '" ;
355- sendResponse (request, msg, WIFI_AP);
362+ sendResponse (request, msg);
363+ changeWifiMode (WIFI_AP);
356364 }
357365}
358366
@@ -531,8 +539,8 @@ static void WebMAVLinkHandler(AsyncWebServerRequest *request)
531539 json[" counters" ][" packets_up" ] = stats->packets_uplink ;
532540 json[" counters" ][" drops_down" ] = stats->drops_downlink ;
533541 json[" counters" ][" overflows_down" ] = stats->overflows_downlink ;
534- json[" ports" ][" listen" ] = MAVLINK_PORT_LISTEN ;
535- json[" ports" ][" send" ] = MAVLINK_PORT_SEND ;
542+ json[" ports" ][" listen" ] = config. GetMavlinkListenPort () ;
543+ json[" ports" ][" send" ] = config. GetMavlinkSendPort () ;
536544 if (gcsIPSet) {
537545 json[" ip" ][" gcs" ] = gcsIP.toString ();
538546 } else {
@@ -544,6 +552,35 @@ static void WebMAVLinkHandler(AsyncWebServerRequest *request)
544552 serializeJson (json, *response);
545553 request->send (response);
546554}
555+
556+ static void WebUpdateSetMavLink (AsyncWebServerRequest *request)
557+ {
558+ uint16_t listen_port = request->arg (" listen" ).toInt ();
559+ uint16_t send_port = request->arg (" send" ).toInt ();
560+
561+ DBGLN (" Setting MavLink configuration: listen=%d, send=%d" , listen_port, send_port);
562+
563+ config.SetMavlinkListenPort (listen_port);
564+ config.SetMavlinkSendPort (send_port);
565+ config.SetWiFiService (WIFI_SERVICE_MAVLINK_TX);
566+ config.Commit ();
567+
568+ // Restart MavLink UDP service
569+ mavlinkUDP.stop ();
570+ mavlinkUDP.begin (config.GetMavlinkListenPort ());
571+
572+ String response = F (
573+ " <html><head>"
574+ " <meta http-equiv='refresh' content='2;url=/'>"
575+ " <title>MavLink Settings Updated</title>"
576+ " </head><body>"
577+ " <h1>MavLink Settings Updated Successfully</h1>"
578+ " <p>Redirecting back to the main page in 2 seconds...</p>"
579+ " </body></html>"
580+ );
581+
582+ sendResponse (request, response, " text/html" );
583+ }
547584#endif
548585
549586static void wifiOff ()
@@ -666,6 +703,9 @@ static void startServices()
666703 server.on (" /config" , HTTP_GET, GetConfiguration);
667704 server.on (" /networks.json" , WebUpdateSendNetworks);
668705 server.on (" /sethome" , WebUpdateSetHome);
706+ #if defined(MAVLINK_ENABLED)
707+ server.on (" /setmavlink" , WebUpdateSetMavLink);
708+ #endif
669709 server.on (" /forget" , WebUpdateForget);
670710 server.on (" /connect" , WebUpdateConnect);
671711 server.on (" /access" , WebUpdateAccessPoint);
@@ -708,7 +748,7 @@ static void startServices()
708748
709749 startMDNS ();
710750#if defined(MAVLINK_ENABLED)
711- mavlinkUDP.begin (MAVLINK_PORT_LISTEN );
751+ mavlinkUDP.begin (config. GetMavlinkListenPort () );
712752#endif
713753
714754 servicesStarted = true ;
@@ -824,7 +864,7 @@ static void HandleWebUpdate()
824864 remote = WiFi.broadcastIP ();
825865 }
826866
827- mavlinkUDP.beginPacket (remote, MAVLINK_PORT_SEND );
867+ mavlinkUDP.beginPacket (remote, config. GetMavlinkSendPort () );
828868 mavlink_message_t * msgQueue = mavlink.GetQueuedMsgs ();
829869 for (uint8_t i = 0 ; i < mavlink.GetQueuedMsgCount (); i++)
830870 {
0 commit comments