AP_InertialSensor: fixed build errors on APM2

This commit is contained in:
Andrew Tridgell 2014-08-18 23:11:35 +10:00
parent 15a7f63d7e
commit 7286e7acd2
2 changed files with 4 additions and 2 deletions

View File

@ -177,7 +177,7 @@ uint16_t AP_InertialSensor_L3GD20::_init_sensor( Sample_rate sample_rate )
// TODO: we should probably accept multiple chip
// revisions. This is the one on the PXF
hal.console->printf("L3GD20: unexpected WHOAMI 0x%x\n", (unsigned)whoami);
hal.scheduler->panic("L3GD20: bad WHOAMI");
hal.scheduler->panic(PSTR("L3GD20: bad WHOAMI"));
}
uint8_t tries = 0;

View File

@ -217,7 +217,7 @@ uint16_t AP_InertialSensor_LSM303D::_init_sensor( Sample_rate sample_rate )
// TODO: we should probably accept multiple chip
// revisions. This is the one on the PXF
hal.console->printf("LSM303D: unexpected WHOAMI 0x%x\n", (unsigned)whoami);
hal.scheduler->panic("LSM303D: bad WHOAMI");
hal.scheduler->panic(PSTR("LSM303D: bad WHOAMI"));
}
uint8_t tries = 0;
@ -338,6 +338,8 @@ bool AP_InertialSensor_LSM303D::_data_ready()
if (_drdy_pin_m && _drdy_pin_x) {
return (_drdy_pin_m->read() && _drdy_pin_x->read()) != 0;
}
// TODO: read status register
return false;
}
/**