aboutsummaryrefslogtreecommitdiff
path: root/src/examples
diff options
context:
space:
mode:
authorDaniel Agar <daniel@agar.ca>2014-12-22 17:09:43 -0500
committerDaniel Agar <daniel@agar.ca>2014-12-22 17:56:59 -0500
commitd511e39ea7a3f1e0cb672b14598e18a7df18156a (patch)
tree1c2994b2cc65558bd469b111ffd92eafa5460f15 /src/examples
parentd54b46355ce0f8c128a5e7fce94564c7cb338987 (diff)
downloadpx4-firmware-d511e39ea7a3f1e0cb672b14598e18a7df18156a.tar.gz
px4-firmware-d511e39ea7a3f1e0cb672b14598e18a7df18156a.tar.bz2
px4-firmware-d511e39ea7a3f1e0cb672b14598e18a7df18156a.zip
turn on -Werror and fix resulting errors
Diffstat (limited to 'src/examples')
-rw-r--r--src/examples/fixedwing_control/main.c2
-rw-r--r--src/examples/fixedwing_control/module.mk2
-rw-r--r--src/examples/flow_position_estimator/flow_position_estimator_main.c2
-rw-r--r--src/examples/flow_position_estimator/module.mk2
-rw-r--r--src/examples/hwtest/hwtest.c12
-rw-r--r--src/examples/matlab_csv_serial/matlab_csv_serial.c2
-rw-r--r--src/examples/px4_daemon_app/px4_daemon_app.c9
7 files changed, 20 insertions, 11 deletions
diff --git a/src/examples/fixedwing_control/main.c b/src/examples/fixedwing_control/main.c
index 6a5cbcd30..fcbb54c8e 100644
--- a/src/examples/fixedwing_control/main.c
+++ b/src/examples/fixedwing_control/main.c
@@ -423,7 +423,7 @@ int ex_fixedwing_control_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 20,
2048,
fixedwing_control_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
thread_running = true;
exit(0);
}
diff --git a/src/examples/fixedwing_control/module.mk b/src/examples/fixedwing_control/module.mk
index a2a9eb113..3fab9c8d4 100644
--- a/src/examples/fixedwing_control/module.mk
+++ b/src/examples/fixedwing_control/module.mk
@@ -41,3 +41,5 @@ SRCS = main.c \
params.c
MODULE_STACKSIZE = 1200
+
+EXTRACFLAGS = -Wno-error
diff --git a/src/examples/flow_position_estimator/flow_position_estimator_main.c b/src/examples/flow_position_estimator/flow_position_estimator_main.c
index 0b8c01f79..a89ccf933 100644
--- a/src/examples/flow_position_estimator/flow_position_estimator_main.c
+++ b/src/examples/flow_position_estimator/flow_position_estimator_main.c
@@ -114,7 +114,7 @@ int flow_position_estimator_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 5,
4000,
flow_position_estimator_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/examples/flow_position_estimator/module.mk b/src/examples/flow_position_estimator/module.mk
index 88c9ceb93..5c6e29f8f 100644
--- a/src/examples/flow_position_estimator/module.mk
+++ b/src/examples/flow_position_estimator/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = flow_position_estimator
SRCS = flow_position_estimator_main.c \
flow_position_estimator_params.c
+
+EXTRACFLAGS = -Wno-float-equal
diff --git a/src/examples/hwtest/hwtest.c b/src/examples/hwtest/hwtest.c
index d3b10f46e..95ff346bb 100644
--- a/src/examples/hwtest/hwtest.c
+++ b/src/examples/hwtest/hwtest.c
@@ -39,13 +39,15 @@
* @author Lorenz Meier <lm@inf.ethz.ch>
*/
-#include <nuttx/config.h>
#include <stdio.h>
-#include <systemlib/err.h>
+#include <string.h>
+
#include <drivers/drv_hrt.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/actuator_controls.h>
+#include <nuttx/config.h>
+#include <systemlib/err.h>
#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/uORB.h>
__EXPORT int ex_hwtest_main(int argc, char *argv[]);
@@ -53,7 +55,7 @@ int ex_hwtest_main(int argc, char *argv[])
{
warnx("DO NOT FORGET TO STOP THE COMMANDER APP!");
warnx("(run <commander stop> to do so)");
- warnx("usage: http://px4.io/dev/examples/write_output");
+ warnx("usage: http://px4.io/dev/examples/write_output");
struct actuator_controls_s actuators;
memset(&actuators, 0, sizeof(actuators));
diff --git a/src/examples/matlab_csv_serial/matlab_csv_serial.c b/src/examples/matlab_csv_serial/matlab_csv_serial.c
index c66bebeec..a95f45d1a 100644
--- a/src/examples/matlab_csv_serial/matlab_csv_serial.c
+++ b/src/examples/matlab_csv_serial/matlab_csv_serial.c
@@ -107,7 +107,7 @@ int matlab_csv_serial_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 5,
2000,
matlab_csv_serial_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c
index 3eaf14148..45d541137 100644
--- a/src/examples/px4_daemon_app/px4_daemon_app.c
+++ b/src/examples/px4_daemon_app/px4_daemon_app.c
@@ -38,10 +38,13 @@
* @author Example User <mail@example.com>
*/
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+
#include <nuttx/config.h>
#include <nuttx/sched.h>
-#include <unistd.h>
-#include <stdio.h>
#include <systemlib/systemlib.h>
#include <systemlib/err.h>
@@ -100,7 +103,7 @@ int px4_daemon_app_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
2000,
px4_daemon_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}