mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
Tracker: Unify from print or println to printf.
This commit is contained in:
parent
a73c1daa2e
commit
577d19f91d
@ -390,12 +390,12 @@ void Tracker::load_parameters(void)
|
|||||||
g.format_version != Parameters::k_format_version) {
|
g.format_version != Parameters::k_format_version) {
|
||||||
|
|
||||||
// erase all parameters
|
// erase all parameters
|
||||||
hal.console->println("Firmware change: erasing EEPROM...");
|
hal.console->printf("Firmware change: erasing EEPROM...\n");
|
||||||
AP_Param::erase_all();
|
AP_Param::erase_all();
|
||||||
|
|
||||||
// save the current format version
|
// save the current format version
|
||||||
g.format_version.set_and_save(Parameters::k_format_version);
|
g.format_version.set_and_save(Parameters::k_format_version);
|
||||||
hal.console->println("done.");
|
hal.console->printf("done.\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t before = AP_HAL::micros();
|
uint32_t before = AP_HAL::micros();
|
||||||
|
@ -68,7 +68,7 @@ void Tracker::init_tracker()
|
|||||||
|
|
||||||
if (g.compass_enabled==true) {
|
if (g.compass_enabled==true) {
|
||||||
if (!compass.init() || !compass.read()) {
|
if (!compass.init() || !compass.read()) {
|
||||||
hal.console->println("Compass initialisation failed!");
|
hal.console->printf("Compass initialisation failed!\n");
|
||||||
g.compass_enabled = false;
|
g.compass_enabled = false;
|
||||||
} else {
|
} else {
|
||||||
ahrs.set_compass(&compass);
|
ahrs.set_compass(&compass);
|
||||||
|
Loading…
Reference in New Issue
Block a user