sync posix_sitl_default and posix_sitl_test

This commit is contained in:
Daniel Agar 2016-05-19 00:19:53 -04:00 committed by Lorenz Meier
parent 2487dbfc92
commit 7cf8b3ea1b
5 changed files with 29 additions and 13 deletions

View File

@ -57,6 +57,7 @@ set(config_module_list
modules/systemlib/mixer
modules/uORB
modules/vtol_att_control
lib/controllib
lib/conversion
lib/DriverFramework/framework
@ -72,6 +73,17 @@ set(config_module_list
lib/terrain_estimation
examples/px4_simple_app
#
# Testing
#
modules/commander/commander_tests
modules/controllib_test
#modules/mavlink/mavlink_tests
modules/unit_test
modules/uORB/uORB_tests
systemcmds/tests
)
set(config_extra_builtin_cmds

View File

@ -49,6 +49,7 @@ set(config_module_list
modules/navigator
modules/param
modules/position_estimator_inav
modules/local_position_estimator
modules/sdlog2
modules/sensors
modules/simulator
@ -72,7 +73,7 @@ set(config_module_list
lib/terrain_estimation
examples/px4_simple_app
#
# Testing
#

View File

@ -72,6 +72,7 @@ px4_add_module(
STACK_MAIN 9000
STACK_MAX 9000
COMPILE_FLAGS
-Wno-unused-result
-Wno-float-equal
-Os
SRCS ${srcs}

View File

@ -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;

View File

@ -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");