mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-16 20:47:34 +08:00
@@ -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
|
||||
|
||||
@@ -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;
|
||||
|
||||
|
||||
@@ -732,21 +732,21 @@ FixedwingEstimator::task_main()
|
||||
case 1:
|
||||
{
|
||||
const char* str = "NaN in states, resetting";
|
||||
warnx(str);
|
||||
warnx("%s", str);
|
||||
mavlink_log_critical(_mavlink_fd, str);
|
||||
break;
|
||||
}
|
||||
case 2:
|
||||
{
|
||||
const char* str = "stale IMU data, resetting";
|
||||
warnx(str);
|
||||
warnx("%s", str);
|
||||
mavlink_log_critical(_mavlink_fd, str);
|
||||
break;
|
||||
}
|
||||
case 3:
|
||||
{
|
||||
const char* str = "switching dynamic / static state";
|
||||
warnx(str);
|
||||
warnx("%s", str);
|
||||
mavlink_log_critical(_mavlink_fd, str);
|
||||
break;
|
||||
}
|
||||
|
||||
@@ -635,39 +635,39 @@ 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_mission_sw, &(_parameters.rc_map_mission_sw)) != OK) {
|
||||
warnx(paramerr);
|
||||
warnx("%s", paramerr);
|
||||
}
|
||||
|
||||
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) {
|
||||
@@ -737,12 +737,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));
|
||||
|
||||
@@ -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]);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user