mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_InertialSensor: fixed build errors for LSM9DSO
This commit is contained in:
parent
fa2a1c495e
commit
ea188528fc
@ -789,20 +789,22 @@ void AP_InertialSensor_LSM9DS0::_dump_registers(void)
|
||||
{
|
||||
hal.console->println_P(PSTR("LSM9DS0 registers:"));
|
||||
hal.console->println_P(PSTR("Gyroscope registers:"));
|
||||
for (uint8_t reg=init; reg<=56; reg++) {
|
||||
const uint8_t first = OUT_TEMP_L_XM;
|
||||
const uint8_t last = ACT_DUR;
|
||||
for (uint8_t reg=first; reg<=last; reg++) {
|
||||
uint8_t v = _register_read_g(reg);
|
||||
hal.console->printf_P(PSTR("%02x:%02x "), (unsigned)reg, (unsigned)v);
|
||||
if ((reg - (init-1)) % 16 == 0) {
|
||||
if ((reg - (first-1)) % 16 == 0) {
|
||||
hal.console->println();
|
||||
}
|
||||
}
|
||||
hal.console->println();
|
||||
|
||||
hal.console->println_P(PSTR("Accelerometer and Magnetometers registers:"));
|
||||
for (uint8_t reg=init; reg<=63; reg++) {
|
||||
for (uint8_t reg=first; reg<=last; reg++) {
|
||||
uint8_t v = _register_read_xm(reg);
|
||||
hal.console->printf_P(PSTR("%02x:%02x "), (unsigned)reg, (unsigned)v);
|
||||
if ((reg - (init-1)) % 16 == 0) {
|
||||
if ((reg - (first-1)) % 16 == 0) {
|
||||
hal.console->println();
|
||||
}
|
||||
}
|
||||
@ -811,4 +813,4 @@ void AP_InertialSensor_LSM9DS0::_dump_registers(void)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
#endif // CONFIG_HAL_BOARD
|
||||
|
Loading…
Reference in New Issue
Block a user