diff options
author | Simon Wilks <sjwilks@gmail.com> | 2013-01-22 22:16:41 +0100 |
---|---|---|
committer | Simon Wilks <sjwilks@gmail.com> | 2013-01-22 22:16:41 +0100 |
commit | 8ba3fbd0a3fd98f1db9ffbacccdc405fd29426e0 (patch) | |
tree | 3c2280c303cb042df381bfebb752081cc129ebb2 /apps/px4 | |
parent | ecd01dc2e88a60d71ad87968cd07234a32bf7d8d (diff) | |
parent | cc74874d7ed2f94a030a97b52c91d684f1d4cfa4 (diff) | |
download | px4-firmware-8ba3fbd0a3fd98f1db9ffbacccdc405fd29426e0.tar.gz px4-firmware-8ba3fbd0a3fd98f1db9ffbacccdc405fd29426e0.tar.bz2 px4-firmware-8ba3fbd0a3fd98f1db9ffbacccdc405fd29426e0.zip |
Merged
Diffstat (limited to 'apps/px4')
-rw-r--r-- | apps/px4/tests/test_adc.c | 94 | ||||
-rw-r--r-- | apps/px4/tests/test_bson.c | 2 | ||||
-rw-r--r-- | apps/px4/tests/test_jig_voltages.c | 185 | ||||
-rw-r--r-- | apps/px4/tests/test_sleep.c | 3 | ||||
-rw-r--r-- | apps/px4/tests/test_time.c | 8 | ||||
-rw-r--r-- | apps/px4/tests/tests_file.c | 8 | ||||
-rw-r--r-- | apps/px4/tests/tests_main.c | 70 |
7 files changed, 138 insertions, 232 deletions
diff --git a/apps/px4/tests/test_adc.c b/apps/px4/tests/test_adc.c index c5960e757..4c021303f 100644 --- a/apps/px4/tests/test_adc.c +++ b/apps/px4/tests/test_adc.c @@ -53,96 +53,40 @@ #include "tests.h" #include <nuttx/analog/adc.h> +#include <drivers/drv_adc.h> +#include <systemlib/err.h> int test_adc(int argc, char *argv[]) { - int fd0 = 0; - int ret = 0; - - #pragma pack(push,1) - struct adc_msg4_s { - uint8_t am_channel1; /**< The 8-bit ADC Channel 1 */ - int32_t am_data1; /**< ADC convert result 1 (4 bytes) */ - uint8_t am_channel2; /**< The 8-bit ADC Channel 2 */ - int32_t am_data2; /**< ADC convert result 2 (4 bytes) */ - uint8_t am_channel3; /**< The 8-bit ADC Channel 3 */ - int32_t am_data3; /**< ADC convert result 3 (4 bytes) */ - uint8_t am_channel4; /**< The 8-bit ADC Channel 4 */ - int32_t am_data4; /**< ADC convert result 4 (4 bytes) */ - }; - #pragma pack(pop) - - struct adc_msg4_s sample1; - - ssize_t nbytes; - int j; - int errval; - - fd0 = open("/dev/adc0", O_RDONLY | O_NONBLOCK); - - if (fd0 <= 0) { - message("/dev/adc0 open fail: %d\n", errno); - return ERROR; - - } else { - message("opened /dev/adc0 successfully\n"); - } - usleep(10000); - - for (j = 0; j < 10; j++) { + int fd = open(ADC_DEVICE_PATH, O_RDONLY); - /* sleep 20 milliseconds */ - usleep(20000); - nbytes = read(fd0, &sample1, sizeof(sample1)); + if (fd < 0) + err(1, "can't open ADC device"); - /* Handle unexpected return values */ + for (unsigned i = 0; i < 5; i++) { + /* make space for a maximum of eight channels */ + struct adc_msg_s data[8]; + /* read all channels available */ + ssize_t count = read(fd, data, sizeof(data)); - if (nbytes < 0) { - errval = errno; + if (count < 0) + goto errout_with_dev; - if (errval != EINTR) { - message("reading /dev/adc0 failed: %d\n", errval); - errval = 3; - goto errout_with_dev; - } + unsigned channels = count / sizeof(data[0]); - message("\tinterrupted read..\n"); - - } else if (nbytes == 0) { - message("\tno data read, ignoring.\n"); - ret = ERROR; + for (unsigned j = 0; j < channels; j++) { + printf("%d: %u ", data[j].am_channel, data[j].am_data); } - /* Print the sample data on successful return */ - - else { - if (nbytes != sizeof(sample1)) { - message("\tsample 1 size %d is not matching struct size %d, ignoring\n", - nbytes, sizeof(sample1)); - ret = ERROR; - - } else { - - message("CYCLE %d:\n", j); - - message("channel: %d value: %d\n", - (int)sample1.am_channel1, sample1.am_data1); - message("channel: %d value: %d\n", - (int)sample1.am_channel2, sample1.am_data2); - message("channel: %d value: %d\n", - (int)sample1.am_channel3, sample1.am_data3); - message("channel: %d value: %d\n", - (int)sample1.am_channel4, sample1.am_data4); - } - } - fflush(stdout); + printf("\n"); + usleep(150000); } message("\t ADC test successful.\n"); errout_with_dev: - if (fd0 != 0) close(fd0); + if (fd != 0) close(fd); - return ret; + return OK; } diff --git a/apps/px4/tests/test_bson.c b/apps/px4/tests/test_bson.c index e2a10ec29..a42c462ca 100644 --- a/apps/px4/tests/test_bson.c +++ b/apps/px4/tests/test_bson.c @@ -240,5 +240,5 @@ test_bson(int argc, char *argv[]) decode(&decoder); free(buf); - exit(0); + return OK; }
\ No newline at end of file diff --git a/apps/px4/tests/test_jig_voltages.c b/apps/px4/tests/test_jig_voltages.c index 51f9b9a5b..10c93b264 100644 --- a/apps/px4/tests/test_jig_voltages.c +++ b/apps/px4/tests/test_jig_voltages.c @@ -52,7 +52,8 @@ #include "tests.h" #include <nuttx/analog/adc.h> - +#include <drivers/drv_adc.h> +#include <systemlib/err.h> /**************************************************************************** * Pre-processor Definitions @@ -89,129 +90,79 @@ int test_jig_voltages(int argc, char *argv[]) { - int fd0 = 0; - int ret = OK; - const int nchannels = 4; - - struct adc_msg4_s - { - uint8_t am_channel1; /* The 8-bit ADC Channel */ - int32_t am_data1; /* ADC convert result (4 bytes) */ - uint8_t am_channel2; /* The 8-bit ADC Channel */ - int32_t am_data2; /* ADC convert result (4 bytes) */ - uint8_t am_channel3; /* The 8-bit ADC Channel */ - int32_t am_data3; /* ADC convert result (4 bytes) */ - uint8_t am_channel4; /* The 8-bit ADC Channel */ - int32_t am_data4; /* ADC convert result (4 bytes) */ - }__attribute__((__packed__));; - - struct adc_msg4_s sample1[4]; - - size_t readsize; - ssize_t nbytes; - int i = 0; - int j = 0; - int errval; - - char name[11]; - sprintf(name, "/dev/adc%d", j); - fd0 = open(name, O_RDONLY | O_NONBLOCK); - if (fd0 < 0) - { - printf("ADC: %s open fail\n", name); - return ERROR; - } else { - printf("Opened %s successfully\n", name); + int fd = open(ADC_DEVICE_PATH, O_RDONLY); + int ret = OK; + + if (fd < 0) { + warnx("can't open ADC device"); + return 1; + } + + /* make space for a maximum of eight channels */ + struct adc_msg_s data[8]; + /* read all channels available */ + ssize_t count = read(fd, data, sizeof(data)); + + if (count < 0) { + close(fd); + warnx("can't read from ADC driver. Forgot 'adc start' command?"); + return 1; + } + + unsigned channels = count / sizeof(data[0]); + + for (unsigned j = 0; j < channels; j++) { + printf("%d: %u ", data[j].am_channel, data[j].am_data); } + printf("\n"); + + warnx("\t ADC operational.\n"); /* Expected values */ - int16_t expected_min[] = {2700, 2700, 2200, 2000}; - int16_t expected_max[] = {3000, 3000, 2500, 2200}; - char* check_res[nchannels]; + int16_t expected_min[] = {2800, 2800, 1800, 800}; + int16_t expected_max[] = {3100, 3100, 2100, 1100}; + char *check_res[channels]; - /* first adc read round */ - readsize = 4 * sizeof(struct adc_msg_s); + if (channels < 4) { + close(fd); + warnx("not all four test channels available, aborting."); + return 1; - /* Empty all buffers */ - do { - nbytes = read(fd0, sample1, readsize); + } else { + /* Check values */ + check_res[0] = (expected_min[0] < data[0].am_data && expected_max[0] > data[0].am_data) ? "OK" : "FAIL"; + check_res[1] = (expected_min[1] < data[1].am_data && expected_max[1] > data[1].am_data) ? "OK" : "FAIL"; + check_res[2] = (expected_min[2] < data[2].am_data && expected_max[2] > data[2].am_data) ? "OK" : "FAIL"; + check_res[3] = (expected_min[3] < data[3].am_data && expected_max[3] > data[3].am_data) ? "OK" : "FAIL"; + + /* Accumulate result */ + ret += (expected_min[0] > data[0].am_data || expected_max[0] < data[0].am_data) ? 1 : 0; + ret += (expected_min[1] > data[1].am_data || expected_max[1] < data[1].am_data) ? 1 : 0; + ret += (expected_min[2] > data[2].am_data || expected_max[2] < data[2].am_data) ? 1 : 0; + ret += (expected_min[3] > data[3].am_data || expected_max[3] < data[3].am_data) ? 1 : 0; + + message("Sample:"); + message("channel: %d value: %d (allowed min: %d, allowed max: %d), result: %s\n", + data[0].am_channel, (int)(data[0].am_data), expected_min[0], expected_max[0], check_res[0]); + message("channel: %d value: %d (allowed min: %d, allowed max: %d), result: %s\n", + data[1].am_channel, (int)(data[1].am_data), expected_min[1], expected_max[1], check_res[1]); + message("channel: %d value: %d (allowed min: %d, allowed max: %d), result: %s\n", + data[2].am_channel, (int)(data[2].am_data), expected_min[2], expected_max[2], check_res[2]); + message("channel: %d value: %d (allowed min: %d, allowed max: %d), result: %s\n", + data[3].am_channel, (int)(data[3].am_data), expected_min[3], expected_max[3], check_res[3]); + + if (ret != OK) { + printf("\t JIG voltages test FAILED. Some channels where out of allowed range. Check supply voltages.\n"); + goto errout_with_dev; + } } - while (nbytes > 0); - - up_udelay(20000);//microseconds - /* Take measurements */ - nbytes = read(fd0, sample1, readsize); - - /* Handle unexpected return values */ - - if (nbytes <= 0) - { - errval = errno; - if (errval != EINTR) - { - message("read %s failed: %d\n", - name, errval); - errval = 3; - goto errout_with_dev; - } - - message("\tInterrupted read...\n"); - } - else if (nbytes == 0) - { - message("\tNo data read, Ignoring\n"); - } - - /* Print the sample data on successful return */ - - else - { - int nsamples = nbytes / sizeof(struct adc_msg_s); - if (nsamples * sizeof(struct adc_msg_s) != nbytes) - { - message("\tread size=%d is not a multiple of sample size=%d, Ignoring\n", - nbytes, sizeof(struct adc_msg_s)); - } - else - { - /* Check values */ - check_res[0] = (expected_min[0] < sample1[i].am_data1 && expected_max[0] > sample1[i].am_data1) ? "OK" : "FAIL"; - check_res[1] = (expected_min[1] < sample1[i].am_data2 && expected_max[1] > sample1[i].am_data2) ? "OK" : "FAIL"; - check_res[2] = (expected_min[2] < sample1[i].am_data3 && expected_max[2] > sample1[i].am_data3) ? "OK" : "FAIL"; - check_res[3] = (expected_min[3] < sample1[i].am_data4 && expected_max[3] > sample1[i].am_data4) ? "OK" : "FAIL"; - - /* Accumulate result */ - ret += (expected_min[0] > sample1[i].am_data1 || expected_max[0] < sample1[i].am_data1) ? 1 : 0; - // XXX Chan 11 not connected on test setup - //ret += (expected_min[1] > sample1[i].am_data2 || expected_max[1] < sample1[i].am_data2) ? 1 : 0; - ret += (expected_min[2] > sample1[i].am_data3 || expected_max[2] < sample1[i].am_data3) ? 1 : 0; - ret += (expected_min[3] > sample1[i].am_data4 || expected_max[3] < sample1[i].am_data4) ? 1 : 0; - - message("Sample:"); - message("%d: channel: %d value: %d (allowed min: %d, allowed max: %d), result: %s\n", - i, sample1[i].am_channel1, sample1[i].am_data1, expected_min[0], expected_max[0], check_res[0]); - message("Sample:"); - message("%d: channel: %d value: %d (allowed min: %d, allowed max: %d), result: %s\n", - i, sample1[i].am_channel2, sample1[i].am_data2, expected_min[1], expected_max[1], check_res[1]); - message("Sample:"); - message("%d: channel: %d value: %d (allowed min: %d, allowed max: %d), result: %s\n", - i, sample1[i].am_channel3, sample1[i].am_data3, expected_min[2], expected_max[2], check_res[2]); - message("Sample:"); - message("%d: channel: %d value: %d (allowed min: %d, allowed max: %d), result: %s\n", - i, sample1[i].am_channel4, sample1[i].am_data4, expected_min[3], expected_max[3], check_res[3]); - - if (ret != OK) { - printf("\t ADC test FAILED. Some channels where out of allowed range. Check supply voltages.\n"); - goto errout_with_dev; - } - } - } - - printf("\t ADC test successful.\n"); - - errout_with_dev: - if (fd0 != 0) close(fd0); + + printf("\t JIG voltages test successful.\n"); + +errout_with_dev: + + if (fd != 0) close(fd); return ret; } diff --git a/apps/px4/tests/test_sleep.c b/apps/px4/tests/test_sleep.c index c7b9d2833..ae682b542 100644 --- a/apps/px4/tests/test_sleep.c +++ b/apps/px4/tests/test_sleep.c @@ -90,9 +90,8 @@ int test_sleep(int argc, char *argv[]) printf("\t %d 100ms sleeps\n", nsleeps); fflush(stdout); - for (int i = 0; i < nsleeps; i++) { + for (unsigned int i = 0; i < nsleeps; i++) { usleep(100000); - //printf("\ttick\n"); } printf("\t Sleep test successful.\n"); diff --git a/apps/px4/tests/test_time.c b/apps/px4/tests/test_time.c index 25bf02c31..8a164f3fc 100644 --- a/apps/px4/tests/test_time.c +++ b/apps/px4/tests/test_time.c @@ -95,7 +95,7 @@ cycletime(void) lasttime = cycles; - return (basetime + cycles) / 168; + return (basetime + cycles) / 168; /* XXX magic number */ } /**************************************************************************** @@ -133,9 +133,9 @@ int test_time(int argc, char *argv[]) lowdelta = abs(delta / 100); /* loop checking the time */ - for (unsigned i = 0; i < 100000; i++) { + for (unsigned i = 0; i < 100; i++) { - usleep(rand() * 10); + usleep(rand()); uint32_t flags = irqsave(); @@ -154,7 +154,7 @@ int test_time(int argc, char *argv[]) fprintf(stderr, "h %llu c %llu d %lld\n", h, c, delta - lowdelta); } - printf("Maximum jitter %lld\n", maxdelta); + printf("Maximum jitter %lldus\n", maxdelta); return 0; } diff --git a/apps/px4/tests/tests_file.c b/apps/px4/tests/tests_file.c index 697410cee..6f75b9812 100644 --- a/apps/px4/tests/tests_file.c +++ b/apps/px4/tests/tests_file.c @@ -37,6 +37,7 @@ * File write test. */ +#include <sys/stat.h> #include <stdio.h> #include <unistd.h> #include <fcntl.h> @@ -51,6 +52,13 @@ int test_file(int argc, char *argv[]) { + /* check if microSD card is mounted */ + struct stat buffer; + if (stat("/fs/microsd/", &buffer)) { + warnx("no microSD card mounted, aborting file test"); + return 1; + } + uint8_t buf[512]; hrt_abstime start, end; perf_counter_t wperf = perf_alloc(PC_ELAPSED, "SD writes"); diff --git a/apps/px4/tests/tests_main.c b/apps/px4/tests/tests_main.c index 906d25f9e..ad6828f20 100644 --- a/apps/px4/tests/tests_main.c +++ b/apps/px4/tests/tests_main.c @@ -78,43 +78,44 @@ static int test_jig(int argc, char *argv[]); * Private Data ****************************************************************************/ -struct { +const struct { const char *name; int (* fn)(int argc, char *argv[]); unsigned options; - int passed; #define OPT_NOHELP (1<<0) #define OPT_NOALLTEST (1<<1) #define OPT_NOJIGTEST (1<<2) } tests[] = { - {"led", test_led, 0, 0}, - {"int", test_int, 0, 0}, - {"float", test_float, 0, 0}, - {"sensors", test_sensors, 0, 0}, - {"gpio", test_gpio, OPT_NOJIGTEST | OPT_NOALLTEST, 0}, - {"hrt", test_hrt, OPT_NOJIGTEST | OPT_NOALLTEST, 0}, - {"ppm", test_ppm, OPT_NOJIGTEST | OPT_NOALLTEST, 0}, - {"servo", test_servo, OPT_NOJIGTEST | OPT_NOALLTEST, 0}, - {"adc", test_adc, OPT_NOJIGTEST, 0}, - {"jig_voltages", test_jig_voltages, OPT_NOALLTEST, 0}, - {"uart_loopback", test_uart_loopback, OPT_NOJIGTEST | OPT_NOALLTEST, 0}, - {"uart_baudchange", test_uart_baudchange, OPT_NOJIGTEST | OPT_NOALLTEST, 0}, - {"uart_send", test_uart_send, OPT_NOJIGTEST | OPT_NOALLTEST, 0}, - {"uart_console", test_uart_console, OPT_NOJIGTEST | OPT_NOALLTEST, 0}, - {"hott_telemetry", test_hott_telemetry, OPT_NOJIGTEST | OPT_NOALLTEST, 0}, - {"tone", test_tone, 0, 0}, - {"sleep", test_sleep, OPT_NOJIGTEST, 0}, - {"time", test_time, OPT_NOJIGTEST, 0}, - {"perf", test_perf, OPT_NOJIGTEST, 0}, - {"all", test_all, OPT_NOALLTEST | OPT_NOJIGTEST, 0}, - {"jig", test_jig, OPT_NOJIGTEST | OPT_NOALLTEST, 0}, - {"param", test_param, 0, 0}, - {"bson", test_bson, 0, 0}, - {"file", test_file, 0, 0}, - {"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST, 0}, - {NULL, NULL, 0, 0} + {"led", test_led, 0}, + {"int", test_int, 0}, + {"float", test_float, 0}, + {"sensors", test_sensors, 0}, + {"gpio", test_gpio, OPT_NOJIGTEST | OPT_NOALLTEST}, + {"hrt", test_hrt, OPT_NOJIGTEST | OPT_NOALLTEST}, + {"ppm", test_ppm, OPT_NOJIGTEST | OPT_NOALLTEST}, + {"servo", test_servo, OPT_NOJIGTEST | OPT_NOALLTEST}, + {"adc", test_adc, OPT_NOJIGTEST}, + {"jig_voltages", test_jig_voltages, OPT_NOALLTEST}, + {"uart_loopback", test_uart_loopback, OPT_NOJIGTEST | OPT_NOALLTEST}, + {"uart_baudchange", test_uart_baudchange, OPT_NOJIGTEST | OPT_NOALLTEST}, + {"uart_send", test_uart_send, OPT_NOJIGTEST | OPT_NOALLTEST}, + {"uart_console", test_uart_console, OPT_NOJIGTEST | OPT_NOALLTEST}, + {"hott_telemetry", test_hott_telemetry, OPT_NOJIGTEST | OPT_NOALLTEST}, + {"tone", test_tone, 0}, + {"sleep", test_sleep, OPT_NOJIGTEST}, + {"time", test_time, OPT_NOJIGTEST}, + {"perf", test_perf, OPT_NOJIGTEST}, + {"all", test_all, OPT_NOALLTEST | OPT_NOJIGTEST}, + {"jig", test_jig, OPT_NOJIGTEST | OPT_NOALLTEST}, + {"param", test_param, 0}, + {"bson", test_bson, 0}, + {"file", test_file, 0}, + {"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST}, + {NULL, NULL, 0} }; +#define NTESTS (sizeof(tests) / sizeof(tests[0])) + static int test_help(int argc, char *argv[]) { @@ -134,6 +135,7 @@ test_all(int argc, char *argv[]) unsigned i; char *args[2] = {"all", NULL}; unsigned int failcount = 0; + bool passed[NTESTS]; printf("\nRunning all tests...\n\n"); @@ -148,11 +150,11 @@ test_all(int argc, char *argv[]) fprintf(stderr, " [%s] \t\t\tFAIL\n", tests[i].name); fflush(stderr); failcount++; - + passed[i] = false; } else { - tests[i].passed = 1; printf(" [%s] \t\t\tPASS\n", tests[i].name); fflush(stdout); + passed[i] = true; } } } @@ -196,7 +198,7 @@ test_all(int argc, char *argv[]) unsigned int k; for (k = 0; k < i; k++) { - if ((tests[k].passed == 0) && !(tests[k].options & OPT_NOALLTEST)) { + if (!passed[k] && !(tests[k].options & OPT_NOALLTEST)) { printf(" [%s] to obtain details, please re-run with\n\t nsh> tests %s\n\n", tests[k].name, tests[k].name); } } @@ -243,6 +245,7 @@ int test_jig(int argc, char *argv[]) unsigned i; char *args[2] = {"jig", NULL}; unsigned int failcount = 0; + bool passed[NTESTS]; printf("\nRunning all tests...\n\n"); for (i = 0; tests[i].name; i++) { @@ -255,10 +258,11 @@ int test_jig(int argc, char *argv[]) fprintf(stderr, " [%s] \t\t\tFAIL\n", tests[i].name); fflush(stderr); failcount++; + passed[i] = false; } else { - tests[i].passed = 1; printf(" [%s] \t\t\tPASS\n", tests[i].name); fflush(stdout); + passed[i] = true; } } } @@ -297,7 +301,7 @@ int test_jig(int argc, char *argv[]) unsigned int k; for (k = 0; k < i; k++) { - if ((tests[k].passed == 0) && !(tests[k].options & OPT_NOJIGTEST)) + if (!passed[i] && !(tests[k].options & OPT_NOJIGTEST)) { printf(" [%s] to obtain details, please re-run with\n\t nsh> tests %s\n\n", tests[k].name, tests[k].name); } |