mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_InertialSensor: fixed build errors on APM2
This commit is contained in:
parent
15a7f63d7e
commit
7286e7acd2
@ -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;
|
||||
|
@ -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;
|
||||
}
|
||||
|
||||
/**
|
||||
|
Loading…
Reference in New Issue
Block a user