Files
flix/flix/wifi.ino
Oleg Kalachev dd3575174b Add wifi configuration using parameters and cli
Add console commands to setup wifi.
Add a parameter for choosing between STA and AP mode.
Add parameters for udp ports.
Remove WIFI_ENABLED macro.
2026-01-22 22:58:43 +03:00

77 lines
2.3 KiB
C++

// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Wi-Fi communication
#include <WiFi.h>
#include <WiFiAP.h>
#include <WiFiUdp.h>
#include "Preferences.h"
extern Preferences storage; // use the main preferences storage
const int W_DISABLED = 0, W_AP = 1, W_STA = 2;
int wifiMode = W_AP;
int udpLocalPort = 14550;
int udpRemotePort = 14550;
IPAddress udpRemoteIP = "255.255.255.255";
WiFiUDP udp;
void setupWiFi() {
print("Setup Wi-Fi\n");
if (wifiMode == W_AP) {
WiFi.softAP(storage.getString("WIFI_AP_SSID", "flix").c_str(), storage.getString("WIFI_AP_PASS", "flixwifi").c_str());
} else if (wifiMode == W_STA) {
WiFi.begin(storage.getString("WIFI_STA_SSID", "").c_str(), storage.getString("WIFI_STA_PASS", "").c_str());
}
udp.begin(udpLocalPort);
}
void sendWiFi(const uint8_t *buf, int len) {
if (WiFi.softAPgetStationNum() == 0 && !WiFi.isConnected()) return;
udp.beginPacket(udpRemoteIP, udpRemotePort);
udp.write(buf, len);
udp.endPacket();
}
int receiveWiFi(uint8_t *buf, int len) {
udp.parsePacket();
if (udp.remoteIP()) udpRemoteIP = udp.remoteIP();
return udp.read(buf, len);
}
void printWiFiInfo() {
if (WiFi.getMode() == WIFI_MODE_AP) {
print("Mode: Access Point (AP)\n");
print("MAC: %s\n", WiFi.softAPmacAddress().c_str());
print("SSID: %s\n", WiFi.softAPSSID().c_str());
print("Password: ***\n");
print("Clients: %d\n", WiFi.softAPgetStationNum());
print("IP: %s\n", WiFi.softAPIP().toString().c_str());
} else if (WiFi.getMode() == WIFI_MODE_STA) {
print("Mode: Client (STA)\n");
print("Connected: %d\n", WiFi.isConnected());
print("MAC: %s\n", WiFi.macAddress().c_str());
print("SSID: %s\n", WiFi.SSID().c_str());
print("Password: ***\n");
print("IP: %s\n", WiFi.localIP().toString().c_str());
} else {
print("Mode: Disabled\n");
return;
}
print("Remote IP: %s\n", udpRemoteIP.toString().c_str());
print("MAVLink connected: %d\n", mavlinkConnected);
}
void configWiFi(bool ap, const char *ssid, const char *password) {
if (ap) {
storage.putString("WIFI_AP_SSID", ssid);
storage.putString("WIFI_AP_PASS", password);
} else {
storage.putString("WIFI_STA_SSID", ssid);
storage.putString("WIFI_STA_PASS", password);
}
print("✓ Reboot to apply new settings\n");
}