Merged master into ekf_params

This commit is contained in:
Lorenz Meier 2014-04-26 15:19:21 +02:00
commit 5ad3ff95bf
6 changed files with 26 additions and 19 deletions

View File

@ -1,5 +1,5 @@
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
# Copyright (C) 2012-2014 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@ -125,7 +125,11 @@ ARCHWARNINGS = -Wall \
-Wlogical-op \
-Wmissing-declarations \
-Wpacked \
-Wno-unused-parameter
-Wno-unused-parameter \
-Werror=format-security \
-Werror=array-bounds \
-Wfatal-errors \
-Wformat=1
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
@ -142,7 +146,8 @@ ARCHCWARNINGS = $(ARCHWARNINGS) \
# C++-specific warnings
#
ARCHWARNINGSXX = $(ARCHWARNINGS)
ARCHWARNINGSXX = $(ARCHWARNINGS) \
-Wno-missing-field-initializers
# pull in *just* libm from the toolchain ... this is grody
LIBM := $(shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a)

View File

@ -1015,7 +1015,7 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_GET(0) ... PWM_SERVO_GET(_max_actuators - 1):
/* copy the current output value from the channel */
*(servo_position_t *)arg = Motor[cmd - PWM_SERVO_SET(0)].RawPwmValue;
*(servo_position_t *)arg = Motor[cmd - PWM_SERVO_GET(0)].RawPwmValue;
break;

View File

@ -40,6 +40,7 @@
*/
#include "attitude_estimator_ekf_params.h"
#include <math.h>
/* Extended Kalman Filter covariances */
@ -113,6 +114,7 @@ int parameters_update(const struct attitude_estimator_ekf_param_handles *h, stru
param_get(h->yaw_off, &(p->yaw_off));
param_get(h->mag_decl, &(p->mag_decl));
p->mag_decl *= M_PI / 180.0f;
param_get(h->acc_comp, &(p->acc_comp));

View File

@ -837,21 +837,21 @@ FixedwingEstimator::task_main()
case 1:
{
const char* str = "NaN in states, resetting";
warnx("%s%s", ekfname, str);
warnx("%s", str);
mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str);
break;
}
case 2:
{
const char* str = "stale IMU data, resetting";
warnx("%s%s", ekfname, str);
warnx("%s", str);
mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str);
break;
}
case 3:
{
const char* str = "switching to dynamic state";
warnx("%s%s", ekfname, str);
warnx("%s", str);
mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str);
break;
}
@ -859,7 +859,7 @@ FixedwingEstimator::task_main()
default:
{
const char* str = "unknown reset condition";
warnx("%s%s", ekfname, str);
warnx("%s", str);
mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str);
}
}

View File

@ -627,31 +627,31 @@ Sensors::parameters_update()
/* channel mapping */
if (param_get(_parameter_handles.rc_map_roll, &(_parameters.rc_map_roll)) != OK) {
warnx(paramerr);
warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_pitch, &(_parameters.rc_map_pitch)) != OK) {
warnx(paramerr);
warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_yaw, &(_parameters.rc_map_yaw)) != OK) {
warnx(paramerr);
warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_throttle, &(_parameters.rc_map_throttle)) != OK) {
warnx(paramerr);
warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_mode_sw, &(_parameters.rc_map_mode_sw)) != OK) {
warnx(paramerr);
warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_return_sw, &(_parameters.rc_map_return_sw)) != OK) {
warnx(paramerr);
warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_assisted_sw, &(_parameters.rc_map_assisted_sw)) != OK) {
warnx(paramerr);
warnx("%s", paramerr);
}
if (param_get(_parameter_handles.rc_map_loiter_sw, &(_parameters.rc_map_loiter_sw)) != OK) {
@ -659,7 +659,7 @@ Sensors::parameters_update()
}
if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
warnx(paramerr);
warnx("%s", paramerr);
}
// if (param_get(_parameter_handles.rc_map_offboard_ctrl_mode_sw, &(_parameters.rc_map_offboard_ctrl_mode_sw)) != OK) {
@ -725,12 +725,12 @@ Sensors::parameters_update()
/* scaling of ADC ticks to battery voltage */
if (param_get(_parameter_handles.battery_voltage_scaling, &(_parameters.battery_voltage_scaling)) != OK) {
warnx(paramerr);
warnx("%s", paramerr);
}
/* scaling of ADC ticks to battery current */
if (param_get(_parameter_handles.battery_current_scaling, &(_parameters.battery_current_scaling)) != OK) {
warnx(paramerr);
warnx("%s", paramerr);
}
param_get(_parameter_handles.board_rotation, &(_parameters.board_rotation));

View File

@ -121,7 +121,7 @@ do_device(int argc, char *argv[])
errx(ret,"uORB publications could not be unblocked");
} else {
errx("no valid command: %s", argv[1]);
errx(1, "no valid command: %s", argv[1]);
}
}