mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-23 12:17:35 +08:00
sync posix_sitl_default and posix_sitl_test
This commit is contained in:
committed by
Lorenz Meier
parent
2487dbfc92
commit
7cf8b3ea1b
@@ -72,6 +72,7 @@ px4_add_module(
|
||||
STACK_MAIN 9000
|
||||
STACK_MAX 9000
|
||||
COMPILE_FLAGS
|
||||
-Wno-unused-result
|
||||
-Wno-float-equal
|
||||
-Os
|
||||
SRCS ${srcs}
|
||||
|
||||
@@ -39,13 +39,14 @@
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_posix.h>
|
||||
|
||||
#include <sys/stat.h>
|
||||
#include <poll.h>
|
||||
#include <dirent.h>
|
||||
#include <stdio.h>
|
||||
#include <stddef.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <string.h>
|
||||
@@ -125,7 +126,7 @@ test_file(int argc, char *argv[])
|
||||
uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
|
||||
hrt_abstime start, end;
|
||||
|
||||
int fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
|
||||
int fd = px4_open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
|
||||
|
||||
warnx("testing unaligned writes - please wait..");
|
||||
|
||||
@@ -156,7 +157,7 @@ test_file(int argc, char *argv[])
|
||||
|
||||
warnx("write took %" PRIu64 " us", (end - start));
|
||||
|
||||
close(fd);
|
||||
px4_close(fd);
|
||||
fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_RDONLY);
|
||||
|
||||
/* read back data for validation */
|
||||
@@ -196,7 +197,7 @@ test_file(int argc, char *argv[])
|
||||
|
||||
close(fd);
|
||||
int ret = unlink(PX4_ROOTFSDIR "/fs/microsd/testfile");
|
||||
fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
|
||||
fd = px4_open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
|
||||
|
||||
warnx("testing aligned writes - please wait.. (CTRL^C to abort)");
|
||||
|
||||
@@ -218,7 +219,7 @@ test_file(int argc, char *argv[])
|
||||
|
||||
warnx("reading data aligned..");
|
||||
|
||||
close(fd);
|
||||
px4_close(fd);
|
||||
fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_RDONLY);
|
||||
|
||||
bool align_read_ok = true;
|
||||
|
||||
@@ -39,12 +39,13 @@
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <px4_posix.h>
|
||||
|
||||
#include <sys/stat.h>
|
||||
#include <dirent.h>
|
||||
#include <stdio.h>
|
||||
#include <stddef.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
@@ -200,7 +201,7 @@ test_mount(int argc, char *argv[])
|
||||
|
||||
uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
|
||||
|
||||
int fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
|
||||
int fd = px4_open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
|
||||
|
||||
for (unsigned i = 0; i < iterations; i++) {
|
||||
|
||||
@@ -236,8 +237,8 @@ test_mount(int argc, char *argv[])
|
||||
fsync(fileno(stderr));
|
||||
usleep(200000);
|
||||
|
||||
close(fd);
|
||||
fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_RDONLY);
|
||||
px4_close(fd);
|
||||
fd = px4_open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_RDONLY);
|
||||
|
||||
/* read back data for validation */
|
||||
for (unsigned i = 0; i < iterations; i++) {
|
||||
@@ -267,7 +268,7 @@ test_mount(int argc, char *argv[])
|
||||
}
|
||||
|
||||
int ret = unlink(PX4_ROOTFSDIR "/fs/microsd/testfile");
|
||||
close(fd);
|
||||
px4_close(fd);
|
||||
|
||||
if (ret) {
|
||||
PX4_ERR("UNLINKING FILE FAILED");
|
||||
|
||||
Reference in New Issue
Block a user