Merge pull request #1527 from dagar/Werror

turn on -Werror and fix resulting errors
This commit is contained in:
Lorenz Meier 2014-12-25 17:44:44 +01:00
commit 6fae021a00
48 changed files with 102 additions and 35 deletions

View File

@ -127,6 +127,7 @@ ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x -fno-threadsafe-statics
#
ARCHWARNINGS = -Wall \
-Wextra \
-Werror \
-Wdouble-promotion \
-Wshadow \
-Wfloat-equal \

View File

@ -121,7 +121,7 @@ int ardrone_interface_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 15,
1100,
ardrone_interface_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}

View File

@ -45,6 +45,7 @@
#include "board_config.h"
#include <arch/board/board.h>
#include <systemlib/err.h>
/*
* Ideally we'd be able to get these from up_internal.h,
@ -54,7 +55,7 @@
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
extern void led_init();
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern void led_toggle(int led);

View File

@ -221,7 +221,7 @@ int frsky_telemetry_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
2000,
frsky_telemetry_thread_main,
(const char **)argv);
(char * const *)argv);
while (!thread_running) {
usleep(200);

View File

@ -214,7 +214,7 @@ hott_sensors_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
1024,
hott_sensors_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}

View File

@ -240,7 +240,7 @@ hott_telemetry_main(int argc, char *argv[])
SCHED_PRIORITY_DEFAULT,
2048,
hott_telemetry_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
exit(0);
}

View File

@ -40,3 +40,5 @@ MODULE_COMMAND = px4flow
SRCS = px4flow.cpp
MAXOPTIMIZATION = -Os
EXTRACXXFLAGS = -Wno-attributes

View File

@ -106,7 +106,7 @@ struct i2c_frame {
};
struct i2c_frame f;
typedef struct i2c_integral_frame {
struct i2c_integral_frame {
uint16_t frame_count_since_last_readout;
int16_t pixel_flow_x_integral;
int16_t pixel_flow_y_integral;

View File

@ -109,7 +109,7 @@ int roboclaw_main(int argc, char *argv[])
SCHED_PRIORITY_MAX - 10,
2048,
roboclaw_thread_main,
(const char **)argv);
(char * const *)argv);
exit(0);
} else if (!strcmp(argv[1], "test")) {

View File

@ -206,7 +206,7 @@ static const uint8_t crc_table[] = {
0xfa, 0xfd, 0xf4, 0xf3
};
uint8_t crc8(uint8_t *p, uint8_t len){
static uint8_t crc8(uint8_t *p, uint8_t len) {
uint16_t i;
uint16_t crc = 0x0;

View File

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

View File

@ -41,3 +41,5 @@ SRCS = main.c \
params.c
MODULE_STACKSIZE = 1200
EXTRACFLAGS = -Wframe-larger-than=1200

View File

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

View File

@ -39,3 +39,5 @@ MODULE_COMMAND = flow_position_estimator
SRCS = flow_position_estimator_main.c \
flow_position_estimator_params.c
EXTRACFLAGS = -Wno-float-equal

View File

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

View File

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

View File

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

View File

@ -181,6 +181,11 @@ rotate_3f(enum Rotation rot, float &x, float &y, float &z)
x = tmp;
return;
}
case ROTATION_ROLL_270_YAW_270: {
tmp = z; z = -y; y = tmp;
tmp = x; x = y; y = -tmp;
return;
}
case ROTATION_PITCH_90: {
tmp = z; z = -x; x = tmp;
return;

View File

@ -72,7 +72,7 @@ const char *decode_states[] = {"UNSYNCED",
#define ST24_SCALE_OFFSET (int)(ST24_TARGET_MIN - (ST24_SCALE_FACTOR * ST24_RANGE_MIN + 0.5f))
static enum ST24_DECODE_STATE _decode_state = ST24_DECODE_STATE_UNSYNCED;
static unsigned _rxlen;
static uint8_t _rxlen;
static ReceiverFcPacket _rxpacket;

View File

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

View File

@ -42,3 +42,7 @@ SRCS = attitude_estimator_ekf_main.cpp \
codegen/AttitudeEKF.c
MODULE_STACKSIZE = 1200
EXTRACFLAGS = -Wno-float-equal -Wframe-larger-than=3600
EXTRACXXFLAGS = -Wframe-larger-than=2200

View File

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

View File

@ -8,3 +8,5 @@ SRCS = attitude_estimator_so3_main.cpp \
attitude_estimator_so3_params.c
MODULE_STACKSIZE = 1200
EXTRACXXFLAGS = -Wno-float-equal

View File

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

View File

@ -268,7 +268,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);

View File

@ -51,3 +51,6 @@ SRCS = commander.cpp \
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
EXTRACXXFLAGS = -Wframe-larger-than=1900

View File

@ -42,4 +42,5 @@ SRCS = ekf_att_pos_estimator_main.cpp \
estimator_23states.cpp \
estimator_utilities.cpp
EXTRACXXFLAGS = -Weffc++
EXTRACXXFLAGS = -Weffc++ -Wframe-larger-than=3000

View File

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

View File

@ -47,3 +47,5 @@ SRCS = fw_pos_control_l1_main.cpp \
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
EXTRACXXFLAGS = -Wno-float-equal

View File

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

View File

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

View File

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

View File

@ -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) {

View File

@ -62,3 +62,5 @@ INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
EXTRACXXFLAGS = -Wno-sign-compare

View File

@ -41,3 +41,6 @@ SRCS = position_estimator_inav_main.c \
inertial_filter.c
MODULE_STACKSIZE = 1200
EXTRACFLAGS = -Wframe-larger-than=3500

View File

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

View File

@ -45,3 +45,6 @@ SRCS = sdlog2.c \
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
EXTRACFLAGS = -Wframe-larger-than=1200

View File

@ -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 */

View File

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

View File

@ -44,3 +44,5 @@ SRCS = sensors.cpp \
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
EXTRACXXFLAGS = -Wno-type-limits

View File

@ -57,3 +57,5 @@ SRCS = err.c \
mcu_version.c
MAXOPTIMIZATION = -Os
EXTRACFLAGS = -Wno-sign-compare

View File

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

View File

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

View File

@ -39,3 +39,6 @@ MODULE_COMMAND = vtol_att_control
SRCS = vtol_att_control_main.cpp \
vtol_att_control_params.c
EXTRACXXFLAGS = -Wno-write-strings

View File

@ -41,3 +41,6 @@ SRCS = mixer.cpp
MODULE_STACKSIZE = 4096
MAXOPTIMIZATION = -Os
EXTRACXXFLAGS = -Wframe-larger-than=2048

View File

@ -6,3 +6,6 @@ MODULE_COMMAND = mtd
SRCS = mtd.c 24xxxx_mtd.c
MAXOPTIMIZATION = -Os
EXTRACFLAGS = -Wno-error

View File

@ -212,7 +212,7 @@ static void
do_show(const char* search_string)
{
printf(" + = saved, * = unsaved\n");
param_foreach(do_show_print, search_string, false);
param_foreach(do_show_print, (char *)search_string, false);
exit(0);
}

View File

@ -34,3 +34,6 @@ SRCS = test_adc.c \
test_conv.cpp \
test_mount.c \
test_mtd.c
EXTRACXXFLAGS = -Wframe-larger-than=2500