PX4 Firmware
PX4 Autopilot Software http://px4.io
test_mount.c
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (C) 2012-2019 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file test_mount.c
36  * Device mount / unmount stress test
37  * @author Lorenz Meier <lm@inf.ethz.ch>
38  */
39 
40 #include <px4_platform_common/px4_config.h>
41 #include <px4_platform_common/posix.h>
42 #include <px4_platform_common/tasks.h>
43 
44 #include <sys/stat.h>
45 #include <dirent.h>
46 #include <stdio.h>
47 #include <stddef.h>
48 #include <systemlib/err.h>
49 #include <perf/perf_counter.h>
50 #include <string.h>
51 
52 #include <drivers/drv_hrt.h>
53 
54 #include "tests_main.h"
55 
56 const int fsync_tries = 1;
57 const int abort_tries = 10;
58 
59 int
60 test_mount(int argc, char *argv[])
61 {
62  const unsigned iterations = 2000;
63  const unsigned alignments = 10;
64 
65  const char *cmd_filename = "/fs/microsd/mount_test_cmds.txt";
66 
67 
68  /* check if microSD card is mounted */
69  struct stat buffer;
70 
71  if (stat(PX4_STORAGEDIR "/", &buffer)) {
72  PX4_ERR("no microSD card mounted, aborting file test");
73  return 1;
74  }
75 
76  /* list directory */
77  DIR *d;
78  struct dirent *dir;
79  d = opendir(PX4_STORAGEDIR);
80 
81  if (d) {
82 
83  while ((dir = readdir(d)) != NULL) {
84  //printf("%s\n", dir->d_name);
85  }
86 
87  closedir(d);
88 
89  PX4_INFO("directory listing ok (FS mounted and readable)");
90 
91  } else {
92  /* failed opening dir */
93  PX4_ERR("FAILED LISTING MICROSD ROOT DIRECTORY");
94 
95  if (stat(cmd_filename, &buffer) == OK) {
96  (void)unlink(cmd_filename);
97  }
98 
99  return 1;
100  }
101 
102  /* read current test status from file, write test instructions for next round */
103 
104  /* initial values */
105  int it_left_fsync = fsync_tries;
106  int it_left_abort = abort_tries;
107 
108  int cmd_fd;
109 
110  if (stat(cmd_filename, &buffer) == OK) {
111 
112  /* command file exists, read off state */
113  cmd_fd = open(cmd_filename, O_RDWR | O_NONBLOCK);
114  char buf[64];
115  int ret = read(cmd_fd, buf, sizeof(buf));
116 
117  if (ret > 0) {
118  int count = 0;
119  ret = sscanf(buf, "TEST: %u %u %n", &it_left_fsync, &it_left_abort, &count);
120 
121  } else {
122  buf[0] = '\0';
123  }
124 
125  if (it_left_fsync > fsync_tries) {
126  it_left_fsync = fsync_tries;
127  }
128 
129  if (it_left_abort > abort_tries) {
130  it_left_abort = abort_tries;
131  }
132 
133  PX4_INFO("Iterations left: #%d / #%d of %d / %d\n(%s)", it_left_fsync, it_left_abort,
134  fsync_tries, abort_tries, buf);
135 
136  int it_left_fsync_prev = it_left_fsync;
137 
138  /* now write again what to do next */
139  if (it_left_fsync > 0) {
140  it_left_fsync--;
141  }
142 
143  if (it_left_fsync == 0 && it_left_abort > 0) {
144 
145  it_left_abort--;
146 
147  /* announce mode switch */
148  if (it_left_fsync_prev != it_left_fsync && it_left_fsync == 0) {
149  PX4_INFO("\n SUCCESSFULLY PASSED FSYNC'ED WRITES, CONTINUTING WITHOUT FSYNC");
150  fsync(fileno(stdout));
151  fsync(fileno(stderr));
152  px4_usleep(20000);
153  }
154 
155  }
156 
157  if (it_left_abort == 0) {
158  close(cmd_fd);
159  (void)unlink(cmd_filename);
160  return 0;
161  }
162 
163  } else {
164 
165  /* this must be the first iteration, do something */
166  cmd_fd = open(cmd_filename, O_TRUNC | O_WRONLY | O_CREAT, PX4_O_MODE_666);
167 
168  PX4_INFO("First iteration of file test\n");
169  }
170 
171  char buf[64];
172  (void)sprintf(buf, "TEST: %d %d ", it_left_fsync, it_left_abort);
173  lseek(cmd_fd, 0, SEEK_SET);
174  write(cmd_fd, buf, strlen(buf) + 1);
175  fsync(cmd_fd);
176 
177  /* perform tests for a range of chunk sizes */
178  unsigned chunk_sizes[] = {32, 64, 128, 256, 512, 600, 1200};
179 
180  for (unsigned c = 0; c < (sizeof(chunk_sizes) / sizeof(chunk_sizes[0])); c++) {
181 
182  printf("\n\n====== FILE TEST: %u bytes chunks (%s) ======\n", chunk_sizes[c],
183  (it_left_fsync > 0) ? "FSYNC" : "NO FSYNC");
184  printf("unpower the system immediately (within 0.5s) when the hash (#) sign appears\n");
185  fsync(fileno(stdout));
186  fsync(fileno(stderr));
187  px4_usleep(50000);
188 
189  for (unsigned a = 0; a < alignments; a++) {
190 
191  printf(".");
192 
193  uint8_t write_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
194 
195  /* fill write buffer with known values */
196  for (unsigned i = 0; i < sizeof(write_buf); i++) {
197  /* this will wrap, but we just need a known value with spacing */
198  write_buf[i] = i + 11;
199  }
200 
201  uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
202 
203  int fd = px4_open(PX4_STORAGEDIR "/testfile", O_TRUNC | O_WRONLY | O_CREAT);
204 
205  for (unsigned i = 0; i < iterations; i++) {
206 
207  int wret = write(fd, write_buf + a, chunk_sizes[c]);
208 
209  if (wret != (int)chunk_sizes[c]) {
210  PX4_ERR("WRITE ERROR!");
211 
212  if ((0x3 & (uintptr_t)(write_buf + a))) {
213  PX4_ERR("memory is unaligned, align shift: %d", a);
214  }
215 
216  return 1;
217 
218  }
219 
220  if (it_left_fsync > 0) {
221  fsync(fd);
222 
223  } else {
224  printf("#");
225  fsync(fileno(stdout));
226  fsync(fileno(stderr));
227  }
228  }
229 
230  if (it_left_fsync > 0) {
231  printf("#");
232  }
233 
234  printf(".");
235  fsync(fileno(stdout));
236  fsync(fileno(stderr));
237  px4_usleep(200000);
238 
239  px4_close(fd);
240  fd = px4_open(PX4_STORAGEDIR "/testfile", O_RDONLY);
241 
242  /* read back data for validation */
243  for (unsigned i = 0; i < iterations; i++) {
244  int rret = read(fd, read_buf, chunk_sizes[c]);
245 
246  if (rret != (int)chunk_sizes[c]) {
247  PX4_ERR("READ ERROR!");
248  return 1;
249  }
250 
251  /* compare value */
252  bool compare_ok = true;
253 
254  for (unsigned j = 0; j < chunk_sizes[c]; j++) {
255  if (read_buf[j] != write_buf[j + a]) {
256  PX4_WARN("COMPARISON ERROR: byte %d, align shift: %d", j, a);
257  compare_ok = false;
258  break;
259  }
260  }
261 
262  if (!compare_ok) {
263  PX4_ERR("ABORTING FURTHER COMPARISON DUE TO ERROR");
264  return 1;
265  }
266 
267  }
268 
269  int ret = unlink(PX4_STORAGEDIR "/testfile");
270  px4_close(fd);
271 
272  if (ret) {
273  close(cmd_fd);
274  PX4_ERR("UNLINKING FILE FAILED");
275  return 1;
276  }
277 
278  }
279  }
280 
281  fsync(fileno(stdout));
282  fsync(fileno(stderr));
283  px4_usleep(20000);
284 
285  close(cmd_fd);
286 
287  /* we always reboot for the next test if we get here */
288  PX4_INFO("Iteration done, rebooting..");
289  fsync(fileno(stdout));
290  fsync(fileno(stderr));
291  px4_usleep(50000);
292  px4_systemreset(false);
293 
294  /* never going to get here */
295  return 0;
296 }
const int fsync_tries
Definition: test_mount.c:56
High-resolution timer with callouts and timekeeping.
static void read(bootloader_app_shared_t *pshared)
int test_mount(int argc, char *argv[])
Definition: test_mount.c:60
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
Tests declaration file.
struct __attribute__((__packed__)) reading_msg
Definition: leddar_one.cpp:80
int fd
Definition: dataman.cpp:146
const int abort_tries
Definition: test_mount.c:57
static void write(bootloader_app_shared_t *pshared)
int px4_open(const char *path, int flags,...)
#define OK
Definition: uavcan_main.cpp:71
int px4_close(int fd)
Performance measuring tools.