AP_InertialSensor: compile warnings: format not a string literal, argument types not checked

PSTR() goofs things up when using hal.console->printf_P()
This commit is contained in:
Tom Pittenger 2015-05-03 00:50:12 -07:00 committed by Andrew Tridgell
parent d823541eb1
commit 9e98c68099
3 changed files with 5 additions and 5 deletions

View File

@ -798,7 +798,7 @@ AP_InertialSensor::_init_gyro()
hal.console->println();
for (uint8_t k=0; k<num_gyros; k++) {
if (!converged[k]) {
hal.console->printf_P(PSTR("gyro[%u] did not converge: diff=%f dps\n"),
hal.console->printf_P("gyro[%u] did not converge: diff=%f dps\n",
(unsigned)k, (double)ToDeg(best_diff[k]));
_gyro_offset[k] = best_avg[k];
// flag calibration as failed for this gyro

View File

@ -399,10 +399,10 @@ void AP_InertialSensor_L3GD20::_register_write_check(uint8_t reg, uint8_t val)
_register_write(reg, val);
readed = _register_read(reg);
if (readed != val){
hal.console->printf_P(PSTR("Values doesn't match; written: %02x; read: %02x "), val, readed);
hal.console->printf_P("Values doesn't match; written: %02x; read: %02x ", val, readed);
}
#if L3GD20_DEBUG
hal.console->printf_P(PSTR("Values written: %02x; readed: %02x "), val, readed);
hal.console->printf_P("Values written: %02x; readed: %02x ", val, readed);
#endif
}

View File

@ -480,10 +480,10 @@ void AP_InertialSensor_LSM303D::_register_write_check(uint8_t reg, uint8_t val)
_register_write(reg, val);
readed = _register_read(reg);
if (readed != val){
hal.console->printf_P(PSTR("Values doesn't match; written: %02x; read: %02x "), val, readed);
hal.console->printf_P("Values doesn't match; written: %02x; read: %02x ", val, readed);
}
#if LSM303D_DEBUG
hal.console->printf_P(PSTR("Values written: %02x; readed: %02x "), val, readed);
hal.console->printf_P("Values written: %02x; readed: %02x ", val, readed);
#endif
}