diff options
author | Lorenz Meier <lm@inf.ethz.ch> | 2014-04-26 12:22:13 +0200 |
---|---|---|
committer | Lorenz Meier <lm@inf.ethz.ch> | 2014-04-26 12:22:13 +0200 |
commit | eb520e7dcd7225bcc398847036fe5019c022708b (patch) | |
tree | 08a534781edfbc607c7a21bdcf9ff2accf4b97ef /src/modules | |
parent | b20fe3b2ba6a1aef83dcfaddd54854085b72b5e3 (diff) | |
parent | 267b78f072b105294e28578d2d8bf28e56ff9fc9 (diff) | |
download | px4-firmware-eb520e7dcd7225bcc398847036fe5019c022708b.tar.gz px4-firmware-eb520e7dcd7225bcc398847036fe5019c022708b.tar.bz2 px4-firmware-eb520e7dcd7225bcc398847036fe5019c022708b.zip |
Merge pull request #849 from PX4/compile_pedantic
Compile pedantic
Diffstat (limited to 'src/modules')
-rw-r--r-- | src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp | 6 | ||||
-rw-r--r-- | src/modules/sensors/sensors.cpp | 22 |
2 files changed, 14 insertions, 14 deletions
diff --git a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp b/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp index 8ea611802..46bd399f7 100644 --- a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp +++ b/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp @@ -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; } diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 67c725b1c..214553d19 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -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)); |