diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index b9aac1f684..553757ae36 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -802,7 +802,7 @@ bool AP_InertialSensor::_calculate_trim(const Vector3f &accel_sample, float& tri trim_roll = atan2f(-accel_sample.y, -accel_sample.z); if (fabsf(trim_roll) > radians(10) || fabsf(trim_pitch) > radians(10)) { - hal.console->println("trim over maximum of 10 degrees"); + hal.console->printf("trim over maximum of 10 degrees\n"); return false; } hal.console->printf("Trim OK: roll=%.2f pitch=%.2f\n", @@ -1017,7 +1017,7 @@ AP_InertialSensor::_init_gyro() AP_Notify::flags.initialising = true; // cold start - hal.console->print("Init Gyro"); + hal.console->printf("Init Gyro"); /* we do the gyro calibration with no board rotation. This avoids @@ -1056,7 +1056,7 @@ AP_InertialSensor::_init_gyro() memset(diff_norm, 0, sizeof(diff_norm)); - hal.console->print("*"); + hal.console->printf("*"); for (uint8_t k=0; kprintln(); + hal.console->printf("\n"); for (uint8_t k=0; kprintf("gyro[%u] did not converge: diff=%f dps (expected < %f)\n", @@ -1648,7 +1648,7 @@ void AP_InertialSensor::_acal_save_calibrations() if (fabsf(_trim_roll) > radians(10) || fabsf(_trim_pitch) > radians(10)) { - hal.console->print("ERR: Trim over maximum of 10 degrees!!"); + hal.console->printf("ERR: Trim over maximum of 10 degrees!!"); _new_trim = false; //we have either got faulty level during acal or highly misaligned accelerometers } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp index 2f8376d31c..51775cfa20 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Invensense.cpp @@ -893,7 +893,7 @@ bool AP_InertialSensor_Invensense::_hardware_init(void) _dev->get_semaphore()->give(); if (tries == 5) { - hal.console->println("Failed to boot Invensense 5 times"); + hal.console->printf("Failed to boot Invensense 5 times\n"); return false; } @@ -944,7 +944,7 @@ int AP_Invensense_AuxiliaryBusSlave::passthrough_read(uint8_t reg, uint8_t *buf, assert(buf); if (_registered) { - hal.console->println("Error: can't passthrough when slave is already configured"); + hal.console->printf("Error: can't passthrough when slave is already configured\n"); return -1; } @@ -970,7 +970,7 @@ int AP_Invensense_AuxiliaryBusSlave::passthrough_read(uint8_t reg, uint8_t *buf, int AP_Invensense_AuxiliaryBusSlave::passthrough_write(uint8_t reg, uint8_t val) { if (_registered) { - hal.console->println("Error: can't passthrough when slave is already configured"); + hal.console->printf("Error: can't passthrough when slave is already configured\n"); return -1; } @@ -993,7 +993,7 @@ int AP_Invensense_AuxiliaryBusSlave::passthrough_write(uint8_t reg, uint8_t val) int AP_Invensense_AuxiliaryBusSlave::read(uint8_t *buf) { if (!_registered) { - hal.console->println("Error: can't read before configuring slave"); + hal.console->printf("Error: can't read before configuring slave\n"); return -1; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp index 700acd8881..a0f363a8d3 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_LSM9DS0.cpp @@ -499,7 +499,7 @@ bool AP_InertialSensor_LSM9DS0::_hardware_init() #endif } if (tries == 5) { - hal.console->println("Failed to boot LSM9DS0 5 times\n"); + hal.console->printf("Failed to boot LSM9DS0 5 times\n\n"); goto fail_tries; } @@ -773,28 +773,28 @@ bool AP_InertialSensor_LSM9DS0::update() /* dump all config registers - used for debug */ void AP_InertialSensor_LSM9DS0::_dump_registers(void) { - hal.console->println("LSM9DS0 registers:"); - hal.console->println("Gyroscope registers:"); + hal.console->printf("LSM9DS0 registers:\n"); + hal.console->printf("Gyroscope registers:\n"); 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("%02x:%02x ", (unsigned)reg, (unsigned)v); if ((reg - (first-1)) % 16 == 0) { - hal.console->println(); + hal.console->printf("\n"); } } - hal.console->println(); + hal.console->printf("\n"); - hal.console->println("Accelerometer and Magnetometers registers:"); + hal.console->printf("Accelerometer and Magnetometers registers:\n"); for (uint8_t reg=first; reg<=last; reg++) { uint8_t v = _register_read_xm(reg); hal.console->printf("%02x:%02x ", (unsigned)reg, (unsigned)v); if ((reg - (first-1)) % 16 == 0) { - hal.console->println(); + hal.console->printf("\n"); } } - hal.console->println(); + hal.console->printf("\n"); } #endif diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp index 2a666070ce..7e05a41a03 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp @@ -32,7 +32,7 @@ bool AP_InertialSensor_UserInteract_MAVLink::blocking_read(void) return true; } } - hal.console->println("Timed out waiting for user response"); + hal.console->printf("Timed out waiting for user response\n"); _gcs->set_snoop(nullptr); return false; }