mirror of
https://github.com/okalachev/flix.git
synced 2025-08-17 09:06:11 +00:00
Add WIFI_UDP_ALWAYS_BROADCAST define
This commit is contained in:
@@ -40,6 +40,7 @@ const char* motd =
|
|||||||
"cr - calibrate RC\n"
|
"cr - calibrate RC\n"
|
||||||
"ca - calibrate accel\n"
|
"ca - calibrate accel\n"
|
||||||
"mfr, mfl, mrr, mrl - test motor (remove props)\n"
|
"mfr, mfl, mrr, mrl - test motor (remove props)\n"
|
||||||
|
"wifi - show Wi-Fi info\n"
|
||||||
"sys - show system info\n"
|
"sys - show system info\n"
|
||||||
"reset - reset drone's state\n"
|
"reset - reset drone's state\n"
|
||||||
"reboot - reboot the drone\n";
|
"reboot - reboot the drone\n";
|
||||||
@@ -141,6 +142,8 @@ void doCommand(String str, bool echo = false) {
|
|||||||
testMotor(MOTOR_REAR_RIGHT);
|
testMotor(MOTOR_REAR_RIGHT);
|
||||||
} else if (command == "mrl") {
|
} else if (command == "mrl") {
|
||||||
testMotor(MOTOR_REAR_LEFT);
|
testMotor(MOTOR_REAR_LEFT);
|
||||||
|
} else if (command == "wifi") {
|
||||||
|
printWiFiInfo();
|
||||||
} else if (command == "sys") {
|
} else if (command == "sys") {
|
||||||
#ifdef ESP32
|
#ifdef ESP32
|
||||||
print("Chip: %s\n", ESP.getChipModel());
|
print("Chip: %s\n", ESP.getChipModel());
|
||||||
|
@@ -13,6 +13,7 @@
|
|||||||
#define WIFI_PASSWORD "flixwifi"
|
#define WIFI_PASSWORD "flixwifi"
|
||||||
#define WIFI_UDP_PORT 14550
|
#define WIFI_UDP_PORT 14550
|
||||||
#define WIFI_UDP_REMOTE_PORT 14550
|
#define WIFI_UDP_REMOTE_PORT 14550
|
||||||
|
#define WIFI_UDP_ALWAYS_BROADCAST 1
|
||||||
|
|
||||||
WiFiUDP udp;
|
WiFiUDP udp;
|
||||||
|
|
||||||
@@ -24,7 +25,9 @@ void setupWiFi() {
|
|||||||
|
|
||||||
void sendWiFi(const uint8_t *buf, int len) {
|
void sendWiFi(const uint8_t *buf, int len) {
|
||||||
if (WiFi.softAPIP() == IPAddress(0, 0, 0, 0) && WiFi.status() != WL_CONNECTED) return;
|
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.write(buf, len);
|
||||||
udp.endPacket();
|
udp.endPacket();
|
||||||
}
|
}
|
||||||
@@ -34,4 +37,13 @@ int receiveWiFi(uint8_t *buf, int len) {
|
|||||||
return udp.read(buf, 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
|
#endif
|
||||||
|
@@ -72,4 +72,5 @@ void calibrateGyro() { print("Skip gyro calibrating\n"); };
|
|||||||
void calibrateAccel() { print("Skip accel calibrating\n"); };
|
void calibrateAccel() { print("Skip accel calibrating\n"); };
|
||||||
void printIMUCalibration() { print("cal: N/A\n"); };
|
void printIMUCalibration() { print("cal: N/A\n"); };
|
||||||
void printIMUInfo() {};
|
void printIMUInfo() {};
|
||||||
|
void printWiFiInfo() {};
|
||||||
Vector accBias, gyroBias, accScale(1, 1, 1);
|
Vector accBias, gyroBias, accScale(1, 1, 1);
|
||||||
|
Reference in New Issue
Block a user