aboutsummaryrefslogtreecommitdiff
path: root/src/systemcmds/tests
diff options
context:
space:
mode:
authorDon Gagne <don@thegagnes.com>2014-06-29 17:47:24 -0700
committerDon Gagne <don@thegagnes.com>2014-06-29 17:47:24 -0700
commit92adbe9216c96c53d1baa4eb1e14b4ede272c080 (patch)
treea5167e5c336b4f8fcb1550317c7e26da7bfedbfe /src/systemcmds/tests
parent28a31708f98eefa4ceb04617f2da3dd7892c99fa (diff)
downloadpx4-firmware-92adbe9216c96c53d1baa4eb1e14b4ede272c080.tar.gz
px4-firmware-92adbe9216c96c53d1baa4eb1e14b4ede272c080.tar.bz2
px4-firmware-92adbe9216c96c53d1baa4eb1e14b4ede272c080.zip
Fix compiler warnings
Diffstat (limited to 'src/systemcmds/tests')
-rw-r--r--src/systemcmds/tests/test_conv.cpp2
-rw-r--r--src/systemcmds/tests/test_file.c7
-rw-r--r--src/systemcmds/tests/test_file2.c10
-rw-r--r--src/systemcmds/tests/test_float.c10
-rw-r--r--src/systemcmds/tests/test_mathlib.cpp4
-rw-r--r--src/systemcmds/tests/test_mixer.cpp33
-rw-r--r--src/systemcmds/tests/test_ppm_loopback.c1
-rw-r--r--src/systemcmds/tests/test_rc.c1
-rw-r--r--src/systemcmds/tests/test_servo.c1
9 files changed, 26 insertions, 43 deletions
diff --git a/src/systemcmds/tests/test_conv.cpp b/src/systemcmds/tests/test_conv.cpp
index 50dece816..0ecdc8eb9 100644
--- a/src/systemcmds/tests/test_conv.cpp
+++ b/src/systemcmds/tests/test_conv.cpp
@@ -65,7 +65,7 @@ int test_conv(int argc, char *argv[])
float f = i/10000.0f;
float fres = REG_TO_FLOAT(FLOAT_TO_REG(f));
if (fabsf(f - fres) > 0.0001f) {
- warnx("conversion fail: input: %8.4f, intermediate: %d, result: %8.4f", f, REG_TO_SIGNED(FLOAT_TO_REG(f)), fres);
+ warnx("conversion fail: input: %8.4f, intermediate: %d, result: %8.4f", f, REG_TO_SIGNED(FLOAT_TO_REG(f)), (double)fres);
return 1;
}
}
diff --git a/src/systemcmds/tests/test_file.c b/src/systemcmds/tests/test_file.c
index 96be1e8df..86f23b485 100644
--- a/src/systemcmds/tests/test_file.c
+++ b/src/systemcmds/tests/test_file.c
@@ -102,7 +102,7 @@ test_file(int argc, char *argv[])
}
/* perform tests for a range of chunk sizes */
- unsigned chunk_sizes[] = {1, 5, 8, 13, 16, 32, 33, 64, 70, 128, 133, 256, 300, 512, 555, 1024, 1500};
+ int chunk_sizes[] = {1, 5, 8, 13, 16, 32, 33, 64, 70, 128, 133, 256, 300, 512, 555, 1024, 1500};
for (unsigned c = 0; c < (sizeof(chunk_sizes) / sizeof(chunk_sizes[0])); c++) {
@@ -116,7 +116,7 @@ test_file(int argc, char *argv[])
uint8_t write_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
/* fill write buffer with known values */
- for (int i = 0; i < sizeof(write_buf); i++) {
+ for (size_t i = 0; i < sizeof(write_buf); i++) {
/* this will wrap, but we just need a known value with spacing */
write_buf[i] = i+11;
}
@@ -224,9 +224,6 @@ test_file(int argc, char *argv[])
return 1;
}
- /* compare value */
- bool compare_ok = true;
-
for (int j = 0; j < chunk_sizes[c]; j++) {
if (read_buf[j] != write_buf[j]) {
warnx("COMPARISON ERROR: byte %d: %u != %u", j, (unsigned int)read_buf[j], (unsigned int)write_buf[j]);
diff --git a/src/systemcmds/tests/test_file2.c b/src/systemcmds/tests/test_file2.c
index ef555f6c3..8db3ea5ae 100644
--- a/src/systemcmds/tests/test_file2.c
+++ b/src/systemcmds/tests/test_file2.c
@@ -49,6 +49,8 @@
#include <stdlib.h>
#include <getopt.h>
+#include "tests.h"
+
#define FLAG_FSYNC 1
#define FLAG_LSEEK 2
@@ -85,9 +87,9 @@ static void test_corruption(const char *filename, uint32_t write_chunk, uint32_t
buffer[j] = get_value(ofs);
ofs++;
}
- if (write(fd, buffer, sizeof(buffer)) != sizeof(buffer)) {
- printf("write failed at offset %u\n", ofs);
- exit(1);
+ if (write(fd, buffer, sizeof(buffer)) != (int)sizeof(buffer)) {
+ printf("write failed at offset %u\n", ofs);
+ exit(1);
}
if (flags & FLAG_FSYNC) {
fsync(fd);
@@ -116,7 +118,7 @@ static void test_corruption(const char *filename, uint32_t write_chunk, uint32_t
printf("read ofs=%u\r", ofs);
}
counter++;
- if (read(fd, buffer, sizeof(buffer)) != sizeof(buffer)) {
+ if (read(fd, buffer, sizeof(buffer)) != (int)sizeof(buffer)) {
printf("read failed at offset %u\n", ofs);
exit(1);
}
diff --git a/src/systemcmds/tests/test_float.c b/src/systemcmds/tests/test_float.c
index 4921c9bbb..e33cc6ef7 100644
--- a/src/systemcmds/tests/test_float.c
+++ b/src/systemcmds/tests/test_float.c
@@ -94,7 +94,7 @@ int test_float(int argc, char *argv[])
printf("\t success: asinf(1.0f) == 1.57079f\n");
} else {
- printf("\t FAIL: asinf(1.0f) != 1.57079f, result: %f\n", asinf_one);
+ printf("\t FAIL: asinf(1.0f) != 1.57079f, result: %f\n", (double)asinf_one);
ret = -1;
}
@@ -128,7 +128,7 @@ int test_float(int argc, char *argv[])
float sinf_zero_one = sinf(0.1f);
- if (fabs(sinf_zero_one - 0.0998334166f) < FLT_EPSILON) {
+ if (fabsf(sinf_zero_one - 0.0998334166f) < FLT_EPSILON) {
printf("\t success: sinf(0.1f) == 0.09983f\n");
} else {
@@ -155,7 +155,7 @@ int test_float(int argc, char *argv[])
}
char sbuf[30];
- sprintf(sbuf, "%8.4f", 0.553415f);
+ sprintf(sbuf, "%8.4f", (double)0.553415f);
if (sbuf[0] == ' ' && sbuf[1] == ' ' && sbuf[2] == '0' &&
sbuf[3] == '.' && sbuf[4] == '5' && sbuf[5] == '5'
@@ -166,7 +166,7 @@ int test_float(int argc, char *argv[])
ret = -5;
}
- sprintf(sbuf, "%8.4f", -0.553415f);
+ sprintf(sbuf, "%8.4f", (double)-0.553415f);
if (sbuf[0] == ' ' && sbuf[1] == '-' && sbuf[2] == '0' &&
sbuf[3] == '.' && sbuf[4] == '5' && sbuf[5] == '5'
@@ -205,7 +205,7 @@ int test_float(int argc, char *argv[])
printf("\t success: (float) 1.55f == 1.55 (double)\n");
} else {
- printf("\t FAIL: (float) 1.55f != 1.55 (double), result: %8.4f\n", f1);
+ printf("\t FAIL: (float) 1.55f != 1.55 (double), result: %8.4f\n", (double)f1);
ret = -8;
}
diff --git a/src/systemcmds/tests/test_mathlib.cpp b/src/systemcmds/tests/test_mathlib.cpp
index 693a208ba..00c649c75 100644
--- a/src/systemcmds/tests/test_mathlib.cpp
+++ b/src/systemcmds/tests/test_mathlib.cpp
@@ -52,10 +52,6 @@
using namespace math;
-const char* formatResult(bool res) {
- return res ? "OK" : "ERROR";
-}
-
int test_mathlib(int argc, char *argv[])
{
warnx("testing mathlib");
diff --git a/src/systemcmds/tests/test_mixer.cpp b/src/systemcmds/tests/test_mixer.cpp
index 0b826b826..8ab8fa2d6 100644
--- a/src/systemcmds/tests/test_mixer.cpp
+++ b/src/systemcmds/tests/test_mixer.cpp
@@ -81,7 +81,7 @@ int test_mixer(int argc, char *argv[])
warnx("testing mixer");
- char *filename = "/etc/mixers/IO_pass.mix";
+ const char *filename = "/etc/mixers/IO_pass.mix";
if (argc > 1)
filename = argv[1];
@@ -100,8 +100,6 @@ int test_mixer(int argc, char *argv[])
* e.g. on PX4IO.
*/
- unsigned nused = 0;
-
const unsigned chunk_size = 64;
MixerGroup mixer_group(mixer_callback, 0);
@@ -124,7 +122,6 @@ int test_mixer(int argc, char *argv[])
return 1;
/* FIRST mark the mixer as invalid */
- bool mixer_ok = false;
/* THEN actually delete it */
mixer_group.reset();
char mixer_text[256]; /* large enough for one mixer */
@@ -140,7 +137,6 @@ int test_mixer(int argc, char *argv[])
/* check for overflow - this would be really fatal */
if ((mixer_text_length + text_length + 1) > sizeof(mixer_text)) {
- bool mixer_ok = false;
return 1;
}
@@ -156,15 +152,6 @@ int test_mixer(int argc, char *argv[])
/* if anything was parsed */
if (resid != mixer_text_length) {
-
- /* only set mixer ok if no residual is left over */
- if (resid == 0) {
- mixer_ok = true;
- } else {
- /* not yet reached the end of the mixer, set as not ok */
- mixer_ok = false;
- }
-
warnx("used %u", mixer_text_length - resid);
/* copy any leftover text to the base of the buffer for re-use */
@@ -192,7 +179,7 @@ int test_mixer(int argc, char *argv[])
should_arm = true;
/* run through arming phase */
- for (int i = 0; i < output_max; i++) {
+ for (unsigned i = 0; i < output_max; i++) {
actuator_controls[i] = 0.1f;
r_page_servo_disarmed[i] = PWM_LOWEST_MIN;
r_page_servo_control_min[i] = PWM_DEFAULT_MIN;
@@ -213,7 +200,7 @@ int test_mixer(int argc, char *argv[])
pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
//warnx("mixed %d outputs (max %d), values:", mixed, output_max);
- for (int i = 0; i < mixed; i++)
+ for (unsigned i = 0; i < mixed; i++)
{
/* check mixed outputs to be zero during init phase */
if (hrt_elapsed_time(&starttime) < INIT_TIME_US &&
@@ -228,7 +215,7 @@ int test_mixer(int argc, char *argv[])
return 1;
}
- //printf("\t %d: %8.4f limited: %8.4f, servo: %d\n", i, outputs_unlimited[i], outputs[i], (int)r_page_servos[i]);
+ //printf("\t %d: %8.4f limited: %8.4f, servo: %d\n", i, (double)outputs_unlimited[i], (double)outputs[i], (int)r_page_servos[i]);
}
usleep(sleep_quantum_us);
sleepcount++;
@@ -244,7 +231,7 @@ int test_mixer(int argc, char *argv[])
for (int j = -jmax; j <= jmax; j++) {
- for (int i = 0; i < output_max; i++) {
+ for (unsigned i = 0; i < output_max; i++) {
actuator_controls[i] = j/10.0f + 0.1f * i;
r_page_servo_disarmed[i] = PWM_LOWEST_MIN;
r_page_servo_control_min[i] = PWM_DEFAULT_MIN;
@@ -257,11 +244,11 @@ int test_mixer(int argc, char *argv[])
pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
warnx("mixed %d outputs (max %d)", mixed, output_max);
- for (int i = 0; i < mixed; i++)
+ for (unsigned i = 0; i < mixed; i++)
{
servo_predicted[i] = 1500 + outputs[i] * (r_page_servo_control_max[i] - r_page_servo_control_min[i]) / 2.0f;
if (fabsf(servo_predicted[i] - r_page_servos[i]) > 2) {
- printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, outputs[i], servo_predicted[i], (int)r_page_servos[i]);
+ printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, (double)outputs[i], servo_predicted[i], (int)r_page_servos[i]);
warnx("mixer violated predicted value");
return 1;
}
@@ -282,7 +269,7 @@ int test_mixer(int argc, char *argv[])
pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
//warnx("mixed %d outputs (max %d), values:", mixed, output_max);
- for (int i = 0; i < mixed; i++)
+ for (unsigned i = 0; i < mixed; i++)
{
/* check mixed outputs to be zero during init phase */
if (r_page_servos[i] != r_page_servo_disarmed[i]) {
@@ -316,7 +303,7 @@ int test_mixer(int argc, char *argv[])
pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
//warnx("mixed %d outputs (max %d), values:", mixed, output_max);
- for (int i = 0; i < mixed; i++)
+ for (unsigned i = 0; i < mixed; i++)
{
/* predict value */
servo_predicted[i] = 1500 + outputs[i] * (r_page_servo_control_max[i] - r_page_servo_control_min[i]) / 2.0f;
@@ -333,7 +320,7 @@ int test_mixer(int argc, char *argv[])
/* check post ramp phase */
if (hrt_elapsed_time(&starttime) > RAMP_TIME_US &&
fabsf(servo_predicted[i] - r_page_servos[i]) > 2) {
- printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, outputs[i], servo_predicted[i], (int)r_page_servos[i]);
+ printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, (double)outputs[i], servo_predicted[i], (int)r_page_servos[i]);
warnx("mixer violated predicted value");
return 1;
}
diff --git a/src/systemcmds/tests/test_ppm_loopback.c b/src/systemcmds/tests/test_ppm_loopback.c
index b9041b013..addd57bea 100644
--- a/src/systemcmds/tests/test_ppm_loopback.c
+++ b/src/systemcmds/tests/test_ppm_loopback.c
@@ -65,7 +65,6 @@ int test_ppm_loopback(int argc, char *argv[])
int _rc_sub = orb_subscribe(ORB_ID(input_rc));
int servo_fd, result;
- servo_position_t data[PWM_OUTPUT_MAX_CHANNELS];
servo_position_t pos;
servo_fd = open(PWM_OUTPUT_DEVICE_PATH, O_RDWR);
diff --git a/src/systemcmds/tests/test_rc.c b/src/systemcmds/tests/test_rc.c
index 57c0e7f4c..c9f9ef439 100644
--- a/src/systemcmds/tests/test_rc.c
+++ b/src/systemcmds/tests/test_rc.c
@@ -52,6 +52,7 @@
#include <arch/board/board.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_rc_input.h>
+#include <drivers/drv_hrt.h>
#include <systemlib/err.h>
#include "tests.h"
diff --git a/src/systemcmds/tests/test_servo.c b/src/systemcmds/tests/test_servo.c
index ef8512bf5..9c6951ca2 100644
--- a/src/systemcmds/tests/test_servo.c
+++ b/src/systemcmds/tests/test_servo.c
@@ -51,6 +51,7 @@
#include <arch/board/board.h>
#include <drivers/drv_pwm_output.h>
+#include <systemlib/err.h>
#include <nuttx/spi.h>