aboutsummaryrefslogtreecommitdiff
path: root/src/modules
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/modules
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/modules')
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp5
-rw-r--r--src/modules/attitude_estimator_ekf/module.mk5
-rwxr-xr-xsrc/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp2
-rw-r--r--src/modules/attitude_estimator_so3/module.mk2
-rw-r--r--src/modules/bottle_drop/bottle_drop.cpp7
-rw-r--r--src/modules/commander/commander.cpp2
-rw-r--r--src/modules/commander/module.mk2
-rw-r--r--src/modules/ekf_att_pos_estimator/module.mk2
-rw-r--r--src/modules/fixedwing_backside/fixedwing_backside_main.cpp2
-rw-r--r--src/modules/fw_pos_control_l1/module.mk2
-rw-r--r--src/modules/mavlink/mavlink_ftp.cpp2
-rw-r--r--src/modules/mavlink/mavlink_ftp.h2
-rw-r--r--src/modules/mavlink/mavlink_main.cpp2
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp3
-rw-r--r--src/modules/navigator/module.mk2
-rw-r--r--src/modules/position_estimator_inav/module.mk2
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c2
-rw-r--r--src/modules/sdlog2/module.mk2
-rw-r--r--src/modules/sdlog2/sdlog2.c4
-rw-r--r--src/modules/segway/segway_main.cpp2
-rw-r--r--src/modules/sensors/module.mk2
-rw-r--r--src/modules/systemlib/module.mk2
-rw-r--r--src/modules/systemlib/systemlib.c2
-rw-r--r--src/modules/systemlib/systemlib.h2
-rw-r--r--src/modules/vtol_att_control/module.mk2
25 files changed, 50 insertions, 14 deletions
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
index 6068ab082..a9205b6fd 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -134,7 +134,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 5,
7200,
attitude_estimator_ekf_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
@@ -275,7 +275,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* keep track of sensor updates */
uint64_t sensor_last_timestamp[3] = {0, 0, 0};
- struct attitude_estimator_ekf_params ekf_params = { 0 };
+ struct attitude_estimator_ekf_params ekf_params;
+ memset(&ekf_params, 0, sizeof(ekf_params));
struct attitude_estimator_ekf_param_handles ekf_param_handles = { 0 };
diff --git a/src/modules/attitude_estimator_ekf/module.mk b/src/modules/attitude_estimator_ekf/module.mk
index 749b0a91c..c4bf34229 100644
--- a/src/modules/attitude_estimator_ekf/module.mk
+++ b/src/modules/attitude_estimator_ekf/module.mk
@@ -42,3 +42,8 @@ SRCS = attitude_estimator_ekf_main.cpp \
codegen/AttitudeEKF.c
MODULE_STACKSIZE = 1200
+
+EXTRACFLAGS = -Wno-float-equal -Wno-error
+
+EXTRACXXFLAGS = -Wno-error
+
diff --git a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
index e49027e47..9414225ca 100755
--- a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
+++ b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
@@ -153,7 +153,7 @@ int attitude_estimator_so3_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 5,
14000,
attitude_estimator_so3_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/modules/attitude_estimator_so3/module.mk b/src/modules/attitude_estimator_so3/module.mk
index f52715abb..7b2e206cc 100644
--- a/src/modules/attitude_estimator_so3/module.mk
+++ b/src/modules/attitude_estimator_so3/module.mk
@@ -8,3 +8,5 @@ SRCS = attitude_estimator_so3_main.cpp \
attitude_estimator_so3_params.c
MODULE_STACKSIZE = 1200
+
+EXTRACXXFLAGS = -Wno-float-equal
diff --git a/src/modules/bottle_drop/bottle_drop.cpp b/src/modules/bottle_drop/bottle_drop.cpp
index e0bcbc6e9..4580b338d 100644
--- a/src/modules/bottle_drop/bottle_drop.cpp
+++ b/src/modules/bottle_drop/bottle_drop.cpp
@@ -523,6 +523,9 @@ BottleDrop::task_main()
}
switch (_drop_state) {
+ case DROP_STATE_INIT:
+ // do nothing
+ break;
case DROP_STATE_TARGET_VALID:
{
@@ -689,6 +692,10 @@ BottleDrop::task_main()
orb_publish(ORB_ID(onboard_mission), _onboard_mission_pub, &_onboard_mission);
}
break;
+
+ case DROP_STATE_BAY_CLOSED:
+ // do nothing
+ break;
}
counter++;
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 744323c01..325ab2a67 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -267,7 +267,7 @@ int commander_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 40,
3200,
commander_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
while (!thread_running) {
usleep(200);
diff --git a/src/modules/commander/module.mk b/src/modules/commander/module.mk
index 27ca5c182..caec1e869 100644
--- a/src/modules/commander/module.mk
+++ b/src/modules/commander/module.mk
@@ -51,3 +51,5 @@ SRCS = commander.cpp \
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
+
+EXTRACXXFLAGS = -Wno-error
diff --git a/src/modules/ekf_att_pos_estimator/module.mk b/src/modules/ekf_att_pos_estimator/module.mk
index 36d854ddd..07e70ddb3 100644
--- a/src/modules/ekf_att_pos_estimator/module.mk
+++ b/src/modules/ekf_att_pos_estimator/module.mk
@@ -42,4 +42,4 @@ SRCS = ekf_att_pos_estimator_main.cpp \
estimator_23states.cpp \
estimator_utilities.cpp
-EXTRACXXFLAGS = -Weffc++
+EXTRACXXFLAGS = -Weffc++ -Wno-error
diff --git a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
index f4ea05088..71b387b1e 100644
--- a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
+++ b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
@@ -115,7 +115,7 @@ int fixedwing_backside_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 10,
5120,
control_demo_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/modules/fw_pos_control_l1/module.mk b/src/modules/fw_pos_control_l1/module.mk
index 440bab2c5..98e5c0a1e 100644
--- a/src/modules/fw_pos_control_l1/module.mk
+++ b/src/modules/fw_pos_control_l1/module.mk
@@ -47,3 +47,5 @@ SRCS = fw_pos_control_l1_main.cpp \
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
+
+EXTRACXXFLAGS = -Wno-float-equal
diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp
index f17497aa8..4ba595a87 100644
--- a/src/modules/mavlink/mavlink_ftp.cpp
+++ b/src/modules/mavlink/mavlink_ftp.cpp
@@ -801,7 +801,7 @@ MavlinkFTP::_return_request(Request *req)
/// @brief Copy file (with limited space)
int
-MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, ssize_t length)
+MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, size_t length)
{
char buff[512];
int src_fd = -1, dst_fd = -1;
diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h
index bef6775a9..9693a92a9 100644
--- a/src/modules/mavlink/mavlink_ftp.h
+++ b/src/modules/mavlink/mavlink_ftp.h
@@ -142,7 +142,7 @@ private:
static void _worker_trampoline(void *arg);
void _process_request(Request *req);
void _reply(Request *req);
- int _copy_file(const char *src_path, const char *dst_path, ssize_t length);
+ int _copy_file(const char *src_path, const char *dst_path, size_t length);
ErrorCode _workList(PayloadHeader *payload);
ErrorCode _workOpen(PayloadHeader *payload, int oflag);
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 29b7ec7b7..08a9ac76b 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -1638,7 +1638,7 @@ Mavlink::start(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
2800,
(main_t)&Mavlink::start_helper,
- (const char **)argv);
+ (char * const *)argv);
// Ensure that this shell command
// does not return before the instance
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 378e3427d..2203ea1e7 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -1764,6 +1764,9 @@ protected:
case RC_INPUT_SOURCE_PX4IO_ST24:
msg.rssi |= (3 << 4);
break;
+ case RC_INPUT_SOURCE_UNKNOWN:
+ // do nothing
+ break;
}
if (rc.rc_lost) {
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index c44d4c35e..0d7d6b9ef 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -62,3 +62,5 @@ INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
+
+EXTRACXXFLAGS = -Wno-sign-compare
diff --git a/src/modules/position_estimator_inav/module.mk b/src/modules/position_estimator_inav/module.mk
index 0658d3f09..5ebdb721c 100644
--- a/src/modules/position_estimator_inav/module.mk
+++ b/src/modules/position_estimator_inav/module.mk
@@ -41,3 +41,5 @@ SRCS = position_estimator_inav_main.c \
inertial_filter.c
MODULE_STACKSIZE = 1200
+
+EXTRACFLAGS = -Wno-error
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 0af01cba1..43829ede5 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -151,7 +151,7 @@ int position_estimator_inav_main(int argc, char *argv[])
position_estimator_inav_task = task_spawn_cmd("position_estimator_inav",
SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 5000,
position_estimator_inav_thread_main,
- (argv) ? (const char **) &argv[2] : (const char **) NULL);
+ (argv) ? (char * const *) &argv[2] : (char * const *) NULL);
exit(0);
}
diff --git a/src/modules/sdlog2/module.mk b/src/modules/sdlog2/module.mk
index d4a00af39..d7224b77a 100644
--- a/src/modules/sdlog2/module.mk
+++ b/src/modules/sdlog2/module.mk
@@ -45,3 +45,5 @@ SRCS = sdlog2.c \
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
+
+EXTRACFLAGS = -Wno-error
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 6df677338..0a8564da6 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -304,7 +304,7 @@ int sdlog2_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT - 30,
3000,
sdlog2_thread_main,
- (const char **)argv);
+ (char * const *)argv);
exit(0);
}
@@ -1089,6 +1089,8 @@ int sdlog2_thread_main(int argc, char *argv[])
if (_extended_logging) {
subs.sat_info_sub = orb_subscribe(ORB_ID(satellite_info));
+ } else {
+ subs.sat_info_sub = 0;
}
/* close non-needed fd's */
diff --git a/src/modules/segway/segway_main.cpp b/src/modules/segway/segway_main.cpp
index 061fbf9b9..ee492f85a 100644
--- a/src/modules/segway/segway_main.cpp
+++ b/src/modules/segway/segway_main.cpp
@@ -110,7 +110,7 @@ int segway_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 10,
5120,
segway_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ (argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}
diff --git a/src/modules/sensors/module.mk b/src/modules/sensors/module.mk
index dfbba92d9..f37bc9327 100644
--- a/src/modules/sensors/module.mk
+++ b/src/modules/sensors/module.mk
@@ -44,3 +44,5 @@ SRCS = sensors.cpp \
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
+
+EXTRACXXFLAGS = -Wno-type-limits
diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk
index fe8b7e75a..f4dff2838 100644
--- a/src/modules/systemlib/module.mk
+++ b/src/modules/systemlib/module.mk
@@ -57,3 +57,5 @@ SRCS = err.c \
mcu_version.c
MAXOPTIMIZATION = -Os
+
+EXTRACFLAGS = -Wno-sign-compare
diff --git a/src/modules/systemlib/systemlib.c b/src/modules/systemlib/systemlib.c
index 90d8dd77c..82183b0d7 100644
--- a/src/modules/systemlib/systemlib.c
+++ b/src/modules/systemlib/systemlib.c
@@ -87,7 +87,7 @@ static void kill_task(FAR struct tcb_s *tcb, FAR void *arg)
kill(tcb->pid, SIGUSR1);
}
-int task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, const char *argv[])
+int task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, char * const argv[])
{
int pid;
diff --git a/src/modules/systemlib/systemlib.h b/src/modules/systemlib/systemlib.h
index 6e22a557e..2f24215a9 100644
--- a/src/modules/systemlib/systemlib.h
+++ b/src/modules/systemlib/systemlib.h
@@ -64,7 +64,7 @@ __EXPORT int task_spawn_cmd(const char *name,
int scheduler,
int stack_size,
main_t entry,
- const char *argv[]);
+ char * const argv[]);
enum MULT_PORTS {
MULT_0_US2_RXTX = 0,
diff --git a/src/modules/vtol_att_control/module.mk b/src/modules/vtol_att_control/module.mk
index 0d5155e90..02403ef76 100644
--- a/src/modules/vtol_att_control/module.mk
+++ b/src/modules/vtol_att_control/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = vtol_att_control
SRCS = vtol_att_control_main.cpp \
vtol_att_control_params.c
+
+EXTRACXXFLAGS = -Wno-error