AP_Compass: Unify from print or println to printf.
This commit is contained in:
parent
2492b9db7e
commit
af47a8e91c
@ -663,7 +663,7 @@ void Compass::_detect_backends(void)
|
||||
|
||||
if (_backend_count == 0 ||
|
||||
_compass_count == 0) {
|
||||
hal.console->println("No Compass backends available");
|
||||
hal.console->printf("No Compass backends available\n");
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -275,7 +275,7 @@ uint8_t Compass::handle_mag_cal_command(const mavlink_command_long_t &packet)
|
||||
case MAV_CMD_DO_START_MAG_CAL: {
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
if (hal.util->get_soft_armed()) {
|
||||
hal.console->println("Disarm for compass calibration");
|
||||
hal.console->printf("Disarm for compass calibration\n");
|
||||
result = MAV_RESULT_FAILED;
|
||||
break;
|
||||
}
|
||||
|
@ -227,7 +227,7 @@ bool AP_Compass_LSM303D::_read_sample()
|
||||
} rx;
|
||||
|
||||
if (_register_read(ADDR_CTRL_REG7) != _reg7_expected) {
|
||||
hal.console->println("LSM303D _read_data_transaction_accel: _reg7_expected unexpected");
|
||||
hal.console->printf("LSM303D _read_data_transaction_accel: _reg7_expected unexpected\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -327,7 +327,7 @@ bool AP_Compass_LSM303D::_hardware_init()
|
||||
}
|
||||
}
|
||||
if (tries == 5) {
|
||||
hal.console->println("Failed to boot LSM303D 5 times");
|
||||
hal.console->printf("Failed to boot LSM303D 5 times\n");
|
||||
goto fail_tries;
|
||||
}
|
||||
|
||||
|
@ -126,15 +126,15 @@ errout:
|
||||
|
||||
void AP_Compass_LSM9DS1::_dump_registers()
|
||||
{
|
||||
hal.console->println("LSMDS1 registers");
|
||||
hal.console->printf("LSMDS1 registers\n");
|
||||
for (uint8_t reg = LSM9DS1M_OFFSET_X_REG_L_M; reg <= LSM9DS1M_INT_THS_H_M; reg++) {
|
||||
uint8_t v = _register_read(reg);
|
||||
hal.console->printf("%02x:%02x ", (unsigned)reg, (unsigned)v);
|
||||
if ((reg - (LSM9DS1M_OFFSET_X_REG_L_M-1)) % 16 == 0) {
|
||||
hal.console->println();
|
||||
hal.console->printf("\n");
|
||||
}
|
||||
}
|
||||
hal.console->println();
|
||||
hal.console->printf("\n");
|
||||
}
|
||||
|
||||
void AP_Compass_LSM9DS1::_update(void)
|
||||
|
@ -15,7 +15,7 @@ uint32_t timer;
|
||||
|
||||
static void setup()
|
||||
{
|
||||
hal.console->println("Compass library test");
|
||||
hal.console->printf("Compass library test\n");
|
||||
|
||||
AP_BoardConfig{}.init(); // initialise the board drivers
|
||||
|
||||
@ -53,7 +53,7 @@ static void loop()
|
||||
hal.console->printf("Compass #%u: ", i);
|
||||
|
||||
if (!compass.healthy()) {
|
||||
hal.console->println("not healthy");
|
||||
hal.console->printf("not healthy\n");
|
||||
continue;
|
||||
}
|
||||
|
||||
@ -93,7 +93,7 @@ static void loop()
|
||||
|
||||
hal.console->printf(" t=%u", (unsigned)read_time);
|
||||
|
||||
hal.console->println();
|
||||
hal.console->printf("\n");
|
||||
}
|
||||
} else {
|
||||
hal.scheduler->delay(1);
|
||||
|
Loading…
Reference in New Issue
Block a user