From 5efd704aad4fd706286a274c469a3b9681d490c3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 27 Apr 2024 11:43:26 +1000 Subject: [PATCH] test: added parse_tlog for performance testing --- generator/C/test/posix/Makefile | 3 ++ generator/C/test/posix/parse_tlog.c | 59 +++++++++++++++++++++++++++++ 2 files changed, 62 insertions(+) create mode 100644 generator/C/test/posix/parse_tlog.c diff --git a/generator/C/test/posix/Makefile b/generator/C/test/posix/Makefile index f1b993fcd..12794da0d 100644 --- a/generator/C/test/posix/Makefile +++ b/generator/C/test/posix/Makefile @@ -50,3 +50,6 @@ testmav2.0_minimal: testmav.c sha256_test: sha256_test.c $(CC) $(CFLAGS) -I../../include_v2.0 -o $@ sha256_test.c + +parse_tlog: parse_tlog.c + $(CC) $(CFLAGS) -I../../include_v2.0 -I../../include_v2.0/minimal -o $@ parse_tlog.c diff --git a/generator/C/test/posix/parse_tlog.c b/generator/C/test/posix/parse_tlog.c new file mode 100644 index 000000000..160a4f367 --- /dev/null +++ b/generator/C/test/posix/parse_tlog.c @@ -0,0 +1,59 @@ +/* + parse a tlog, for performance testing + */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define MAVLINK_USE_CONVENIENCE_FUNCTIONS +#define MAVLINK_USE_MESSAGE_INFO +#define MAVLINK_COMM_NUM_BUFFERS 2 + +// this trick allows us to make mavlink_message_t as small as possible +// for this dialect, which saves some memory +#include +#define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE + +#include +static mavlink_system_t mavlink_system = {42,11,}; + +#define MAVLINK_ASSERT(x) assert(x) +static void comm_send_ch(mavlink_channel_t chan, uint8_t c) {} + +#include + +int main(int argc, const char *argv[]) +{ + if (argc < 2) { + printf("Usage: parse_tlog FILENAME\n"); + exit(1); + } + const char *filename = argv[1]; + int fd = open(filename, O_RDONLY); + if (fd == -1) { + perror(filename); + exit(1); + } + mavlink_channel_t chan = MAVLINK_COMM_0; + char c; + uint32_t msg_count = 0; + mavlink_message_t last_msg; + mavlink_status_t status; + + while (read(fd, &c, 1) == 1) { + if (mavlink_parse_char(chan, c, &last_msg, &status)) { + msg_count++; + } + } + printf("parsed %u messages\n", (unsigned)msg_count); + + return 0; +} +