AP_InertialSensor: fixed PSTR handling

must use PSTR on code compiled for AVR
This commit is contained in:
Andrew Tridgell 2015-05-05 13:54:00 +10:00
parent 31693e332e
commit 089e63f987
3 changed files with 4 additions and 4 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("gyro[%u] did not converge: diff=%f dps\n",
hal.console->printf_P(PSTR("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

@ -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("Values doesn't match; written: %02x; read: %02x ", val, readed);
hal.console->printf("Values doesn't match; written: %02x; read: %02x ", val, readed);
}
#if LSM303D_DEBUG
hal.console->printf_P("Values written: %02x; readed: %02x ", val, readed);
hal.console->printf("Values written: %02x; readed: %02x ", val, readed);
#endif
}

View File

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