From a090e3543c9a4d3bd6568adbfa51300696eedd18 Mon Sep 17 00:00:00 2001 From: Oleg Kalachev Date: Tue, 29 Jul 2025 18:08:57 +0300 Subject: [PATCH] Add WIFI_UDP_ALWAYS_BROADCAST define --- flix/cli.ino | 3 +++ flix/wifi.ino | 14 +++++++++++++- gazebo/flix.h | 1 + 3 files changed, 17 insertions(+), 1 deletion(-) diff --git a/flix/cli.ino b/flix/cli.ino index 5e99b09..73fdb51 100644 --- a/flix/cli.ino +++ b/flix/cli.ino @@ -40,6 +40,7 @@ const char* motd = "cr - calibrate RC\n" "ca - calibrate accel\n" "mfr, mfl, mrr, mrl - test motor (remove props)\n" +"wifi - show Wi-Fi info\n" "sys - show system info\n" "reset - reset drone's state\n" "reboot - reboot the drone\n"; @@ -141,6 +142,8 @@ void doCommand(String str, bool echo = false) { testMotor(MOTOR_REAR_RIGHT); } else if (command == "mrl") { testMotor(MOTOR_REAR_LEFT); + } else if (command == "wifi") { + printWiFiInfo(); } else if (command == "sys") { #ifdef ESP32 print("Chip: %s\n", ESP.getChipModel()); diff --git a/flix/wifi.ino b/flix/wifi.ino index e0d2957..9f6bc21 100644 --- a/flix/wifi.ino +++ b/flix/wifi.ino @@ -13,6 +13,7 @@ #define WIFI_PASSWORD "flixwifi" #define WIFI_UDP_PORT 14550 #define WIFI_UDP_REMOTE_PORT 14550 +#define WIFI_UDP_ALWAYS_BROADCAST 1 WiFiUDP udp; @@ -24,7 +25,9 @@ void setupWiFi() { void sendWiFi(const uint8_t *buf, int len) { if (WiFi.softAPIP() == IPAddress(0, 0, 0, 0) && WiFi.status() != WL_CONNECTED) return; - udp.beginPacket(WiFi.softAPBroadcastIP(), WIFI_UDP_REMOTE_PORT); + IPAddress remote = WiFi.softAPBroadcastIP(); + if (!WIFI_UDP_ALWAYS_BROADCAST && udp.remoteIP()) remote = udp.remoteIP(); + udp.beginPacket(remote, WIFI_UDP_REMOTE_PORT); udp.write(buf, len); udp.endPacket(); } @@ -34,4 +37,13 @@ int receiveWiFi(uint8_t *buf, int len) { return udp.read(buf, len); } +void printWiFiInfo() { + print("SSID: %s\n", WiFi.softAPSSID().c_str()); + print("Clients: %d\n", WiFi.softAPgetStationNum()); + print("Status: %d\n", WiFi.status()); + print("IP: %s\n", WiFi.softAPIP().toString().c_str()); + print("Remote IP: %s\n", udp.remoteIP().toString().c_str()); + print("Broadcast IP: %s\n", WiFi.softAPBroadcastIP().toString().c_str()); +} + #endif diff --git a/gazebo/flix.h b/gazebo/flix.h index 9dbfa2b..ce82c38 100644 --- a/gazebo/flix.h +++ b/gazebo/flix.h @@ -72,4 +72,5 @@ void calibrateGyro() { print("Skip gyro calibrating\n"); }; void calibrateAccel() { print("Skip accel calibrating\n"); }; void printIMUCalibration() { print("cal: N/A\n"); }; void printIMUInfo() {}; +void printWiFiInfo() {}; Vector accBias, gyroBias, accScale(1, 1, 1);