39 #include <px4_platform_common/defines.h> 49 #include <px4_platform_common/getopt.h> 56 #define LOG_PATH PX4_STORAGEDIR 68 return u.buf[ofs % 4];
71 static int test_corruption(
const char *filename, uint32_t write_chunk, uint32_t write_size, uint16_t flags)
73 printf(
"Testing on %s with write_chunk=%u write_size=%u\n",
74 filename, (
unsigned)write_chunk, (
unsigned)write_size);
77 int fd = open(filename, O_CREAT | O_RDWR | O_TRUNC, PX4_O_MODE_666);
87 while (ofs < write_size) {
88 uint8_t buffer[write_chunk];
90 for (uint16_t j = 0; j < write_chunk; j++) {
95 if (
write(fd, buffer,
sizeof(buffer)) != (
int)
sizeof(buffer)) {
96 printf(
"write failed at offset %u\n", ofs);
104 if (counter % 100 == 0) {
105 printf(
"write ofs=%u\r", ofs);
113 printf(
"write ofs=%u\n", ofs);
116 fd = open(filename, O_RDONLY);
126 while (ofs < write_size) {
127 uint8_t buffer[write_chunk];
129 if (counter % 100 == 0) {
130 printf(
"read ofs=%u\r", ofs);
135 if (
read(fd, buffer,
sizeof(buffer)) != (
int)
sizeof(buffer)) {
136 printf(
"read failed at offset %u\n", ofs);
141 for (uint16_t j = 0; j < write_chunk; j++) {
143 printf(
"corruption at ofs=%u got %u\n", ofs, buffer[j]);
152 lseek(fd, 0, SEEK_CUR);
156 printf(
"read ofs=%u\n", ofs);
165 printf(
"test file2 [options] [filename]\n");
166 printf(
"\toptions:\n");
167 printf(
"\t-s SIZE set file size\n");
168 printf(
"\t-c CHUNK set IO chunk size\n");
169 printf(
"\t-F fsync on every write\n");
170 printf(
"\t-L lseek on every read\n");
177 const char *filename =
LOG_PATH "/testfile2.dat";
178 uint32_t write_chunk = 64;
179 uint32_t write_size = 5 * 1024;
182 const char *myoptarg = NULL;
184 while ((opt = px4_getopt(argc, argv,
"c:s:FLh", &myoptind, &myoptarg)) != EOF) {
195 write_size = strtoul(myoptarg, NULL, 0);
199 write_chunk = strtoul(myoptarg, NULL, 0);
220 fprintf(stderr,
"no microSD card mounted, aborting file test");
static int test_corruption(const char *filename, uint32_t write_chunk, uint32_t write_size, uint16_t flags)
static uint8_t get_value(uint32_t ofs)
static void read(bootloader_app_shared_t *pshared)
int test_file2(int argc, char *argv[])
static void write(bootloader_app_shared_t *pshared)
Performance measuring tools.