AP_HAL_VRBRAIN: Unify from print or println to printf.

AP_InertialSensor: Unify from print or printin to printf.
This commit is contained in:
murata 2017-01-21 13:55:04 +09:00 committed by Andrew Tridgell
parent 67fdbf5c2d
commit 0733d760f6
2 changed files with 5 additions and 5 deletions

View File

@ -289,7 +289,7 @@ AP_HAL::AnalogSource* VRBRAINAnalogIn::channel(int16_t pin)
return _channels[j];
}
}
hal.console->println("Out of analog channels");
hal.console->printf("Out of analog channels\n");
return nullptr;
}

View File

@ -21,7 +21,7 @@ void setup(void)
// setup any board specific drivers
BoardConfig.init();
hal.console->println("AP_InertialSensor startup...");
hal.console->printf("AP_InertialSensor startup...\n");
ins.init(100);
@ -33,15 +33,15 @@ void setup(void)
hal.console->printf("Number of detected accels : %u\n", ins.get_accel_count());
hal.console->printf("Number of detected gyros : %u\n\n", ins.get_gyro_count());
hal.console->println("Complete. Reading:");
hal.console->printf("Complete. Reading:\n");
}
void loop(void)
{
int16_t user_input;
hal.console->println();
hal.console->println(
hal.console->printf("\n");
hal.console->printf("%s\n",
"Menu:\n"
" d) display offsets and scaling\n"
" l) level (capture offsets from level)\n"