diff --git a/flix/cli.ino b/flix/cli.ino index 47c0ce8..3dc93cc 100644 --- a/flix/cli.ino +++ b/flix/cli.ino @@ -37,6 +37,7 @@ const char* motd = "disarm - disarm the drone\n" "stab/acro/auto - set mode\n" "rc - show RC data\n" +"wifi - show Wi-Fi info\n" "mot - show motor output\n" "log [dump] - print log header [and data]\n" "cr - calibrate RC\n" @@ -131,6 +132,10 @@ void doCommand(String str, bool echo = false) { controlRoll, controlPitch, controlYaw, controlThrottle, controlMode); print("mode: %s\n", getModeName()); print("armed: %d\n", armed); + } else if (command == "wifi") { +#if WIFI_ENABLED + printWiFiInfo(); +#endif } else if (command == "mot") { print("front-right %g front-left %g rear-right %g rear-left %g\n", motors[MOTOR_FRONT_RIGHT], motors[MOTOR_FRONT_LEFT], motors[MOTOR_REAR_RIGHT], motors[MOTOR_REAR_LEFT]); diff --git a/flix/wifi.ino b/flix/wifi.ino index e003375..30f6d4a 100644 --- a/flix/wifi.ino +++ b/flix/wifi.ino @@ -35,4 +35,15 @@ int receiveWiFi(uint8_t *buf, int len) { return udp.read(buf, len); } +void printWiFiInfo() { + print("MAC: %s\n", WiFi.softAPmacAddress().c_str()); + print("SSID: %s\n", WiFi.softAPSSID().c_str()); + print("Password: %s\n", WIFI_PASSWORD); + 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("MAVLink connected: %d\n", mavlinkConnected); +} + #endif diff --git a/gazebo/flix.h b/gazebo/flix.h index 05062d2..be6c750 100644 --- a/gazebo/flix.h +++ b/gazebo/flix.h @@ -73,4 +73,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);