Refactor Wi-Fi log download

Use MAVLink LOG_REQUEST_DATA and LOG_DATA for download log instead of console.
Make Wi-Fi download default way of downloading the log.
Make `log` command only print the header and `log dump` dump the log.
This commit is contained in:
Oleg Kalachev
2025-11-14 20:21:05 +03:00
parent 348721acc9
commit 49039f752d
8 changed files with 70 additions and 19 deletions

View File

@@ -32,7 +32,7 @@ simulator: build_simulator
gazebo --verbose ${CURDIR}/gazebo/flix.world gazebo --verbose ${CURDIR}/gazebo/flix.world
log: log:
PORT=$(PORT) tools/grab_log.py tools/log.py
plot: plot:
plotjuggler -d $(shell ls -t tools/log/*.csv | head -n1) plotjuggler -d $(shell ls -t tools/log/*.csv | head -n1)

View File

@@ -2,11 +2,7 @@
Flix quadcopter uses RAM to store flight log data. The default log capacity is 10 seconds at 100 Hz. This configuration can be adjusted in the `log.ino` file. Flix quadcopter uses RAM to store flight log data. The default log capacity is 10 seconds at 100 Hz. This configuration can be adjusted in the `log.ino` file.
To perform log analysis, you need to download the log right after the flight without powering off the drone. Then you can use several tools to analyze the log data. To perform log analysis, you need to download the flight log. To to that, ensure you're connected to the drone using Wi-Fi and run the following command:
## Log download
To download the log, connect the ESP32 using USB right after the flight and run the following command:
```bash ```bash
make log make log

View File

@@ -226,3 +226,13 @@ If the pilot moves the control sticks, the drone will switch back to *STAB* mode
You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*. You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*.
<img src="img/parameters.png" width="400"> <img src="img/parameters.png" width="400">
## Flight log
After the flight, you can download the flight log for analysis wirelessly. Use the following for that:
```bash
make log
```
See more details about log analysis in the [log analysis](log.md) article.

View File

@@ -38,7 +38,7 @@ const char* motd =
"stab/acro/auto - set mode\n" "stab/acro/auto - set mode\n"
"rc - show RC data\n" "rc - show RC data\n"
"mot - show motor output\n" "mot - show motor output\n"
"log - dump in-RAM log\n" "log [dump] - print log header [and data]\n"
"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"
@@ -135,7 +135,8 @@ void doCommand(String str, bool echo = false) {
print("front-right %g front-left %g rear-right %g rear-left %g\n", 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]); motors[MOTOR_FRONT_RIGHT], motors[MOTOR_FRONT_LEFT], motors[MOTOR_REAR_RIGHT], motors[MOTOR_REAR_LEFT]);
} else if (command == "log") { } else if (command == "log") {
dumpLog(); printLogHeader();
if (arg0 == "dump") printLogData();
} else if (command == "cr") { } else if (command == "cr") {
calibrateRC(); calibrateRC();
} else if (command == "ca") { } else if (command == "ca") {

View File

@@ -61,12 +61,13 @@ void logData() {
} }
} }
void dumpLog() { void printLogHeader() {
// Print header
for (int i = 0; i < logColumns; i++) { for (int i = 0; i < logColumns; i++) {
print("%s%s", logEntries[i].name, i < logColumns - 1 ? "," : "\n"); print("%s%s", logEntries[i].name, i < logColumns - 1 ? "," : "\n");
} }
// Print data }
void printLogData() {
for (int i = 0; i < LOG_SIZE; i++) { for (int i = 0; i < LOG_SIZE; i++) {
if (logBuffer[i][0] == 0) continue; // skip empty records if (logBuffer[i][0] == 0) continue; // skip empty records
for (int j = 0; j < logColumns; j++) { for (int j = 0; j < logColumns; j++) {

View File

@@ -210,6 +210,20 @@ void handleMavlink(const void *_msg) {
armed = motors[0] > 0 || motors[1] > 0 || motors[2] > 0 || motors[3] > 0; armed = motors[0] > 0 || motors[1] > 0 || motors[2] > 0 || motors[3] > 0;
} }
if (msg.msgid == MAVLINK_MSG_ID_LOG_REQUEST_DATA) {
mavlink_log_request_data_t m;
mavlink_msg_log_request_data_decode(&msg, &m);
if (m.target_system && m.target_system != SYSTEM_ID) return;
// Send all log records
for (int i = 0; i < sizeof(logBuffer) / sizeof(logBuffer[0]); i++) {
mavlink_message_t msg;
mavlink_msg_log_data_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, 0, i,
sizeof(logBuffer[0]), (uint8_t *)logBuffer[i]);
sendMessage(&msg);
}
}
// Handle commands // Handle commands
if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) { if (msg.msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
mavlink_command_long_t m; mavlink_command_long_t m;

View File

@@ -45,7 +45,8 @@ void normalizeRC();
void calibrateRC(); void calibrateRC();
void calibrateRCChannel(float *channel, uint16_t zero[16], uint16_t max[16], const char *str); void calibrateRCChannel(float *channel, uint16_t zero[16], uint16_t max[16], const char *str);
void printRCCalibration(); void printRCCalibration();
void dumpLog(); void printLogHeader();
void printLogData();
void processMavlink(); void processMavlink();
void sendMavlink(); void sendMavlink();
void sendMessage(const void *msg); void sendMessage(const void *msg);

View File

@@ -3,21 +3,49 @@
# Download flight log remotely and save to file # Download flight log remotely and save to file
import os import os
import time
import datetime import datetime
import struct
from pymavlink.dialects.v20.common import MAVLink_log_data_message
from pyflix import Flix from pyflix import Flix
DIR = os.path.dirname(os.path.realpath(__file__)) DIR = os.path.dirname(os.path.realpath(__file__))
flix = Flix() flix = Flix()
print('Downloading log...') print('Downloading log...')
lines = flix.cli('log').splitlines()
# sort by timestamp header = flix.cli('log')
header = lines.pop(0) print('Received header:\n- ' + '\n- '.join(header.split(',')))
lines.sort(key=lambda line: float(line.split(',')[0]))
records = []
def on_record(msg: MAVLink_log_data_message):
global stop
stop = time.time() + 1 # extend timeout
records.append([])
i = 0
data = bytes(msg.data)
while i + 4 <= msg.count:
records[-1].append(struct.unpack('<f', data[i:i+4])[0])
i += 4
stop = time.time() + 3
flix.on('mavlink.LOG_DATA', on_record)
flix.mavlink.log_request_data_send(flix.system_id, 0, 0, 0, 0xFFFFFFFF)
while time.time() < stop:
time.sleep(1)
flix.off(on_record)
records.sort(key=lambda record: record[0])
records = [record for record in records if record[0] != 0]
print(f'Received records: {len(records)}')
log = open(f'{DIR}/log/{datetime.datetime.now().isoformat()}.csv', 'wb') log = open(f'{DIR}/log/{datetime.datetime.now().isoformat()}.csv', 'wb')
content = header.encode() + b'\n' + b'\n'.join(line.encode() for line in lines) log.write(header.encode() + b'\n')
log.write(content) for record in records:
line = ','.join(f'{value}' for value in record)
log.write(line.encode() + b'\n')
print(f'Written {os.path.relpath(log.name, os.curdir)}') print(f'Written {os.path.relpath(log.name, os.curdir)}')