From 836c8aa68427e03aa2ed683f2e290aea9660fe06 Mon Sep 17 00:00:00 2001 From: murata Date: Sat, 21 Jan 2017 13:50:24 +0900 Subject: [PATCH] RC_Channel: Unify from print or println to printf. --- libraries/RC_Channel/examples/RC_Channel/RC_Channel.cpp | 2 +- libraries/RC_Channel/examples/RC_UART/RC_UART.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/RC_Channel/examples/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/examples/RC_Channel/RC_Channel.cpp index 03f5c1427c..96ef550157 100644 --- a/libraries/RC_Channel/examples/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/examples/RC_Channel/RC_Channel.cpp @@ -19,7 +19,7 @@ static void print_radio_values(); void setup() { - hal.console->println("ArduPilot RC Channel test"); + hal.console->printf("ArduPilot RC Channel test\n"); rc = RC_Channels::rc_channel(CH_1); diff --git a/libraries/RC_Channel/examples/RC_UART/RC_UART.cpp b/libraries/RC_Channel/examples/RC_UART/RC_UART.cpp index 6fc7311e88..528a734cde 100644 --- a/libraries/RC_Channel/examples/RC_UART/RC_UART.cpp +++ b/libraries/RC_Channel/examples/RC_UART/RC_UART.cpp @@ -28,7 +28,7 @@ private: void RC_UART::setup() { hal.scheduler->delay(1000); - hal.console->println("RC_UART starting"); + hal.console->printf("RC_UART starting\n"); hal.UART->begin(baudrate, 512, 512); hal.rcout->set_freq(0xFF, RC_SPEED); }