HAL_AVR: more uart0 -> console changes

This commit is contained in:
Andrew Tridgell 2012-10-27 11:29:11 +11:00
parent d133f15f57
commit 53105efbcd
6 changed files with 6 additions and 8 deletions

View File

@ -21,7 +21,6 @@ uint32_t timer;
void setup() void setup()
{ {
hal.uart0->begin(115200, 128, 128);
hal.console->println("ArduPilot Mega ADC library test"); hal.console->println("ArduPilot Mega ADC library test");
hal.scheduler->delay(1000); hal.scheduler->delay(1000);

View File

@ -24,7 +24,6 @@ AP_Airspeed airspeed;
void setup() void setup()
{ {
hal.uart0->begin(115200, 128, 128);
hal.console->println("ArduPilot Airspeed library test"); hal.console->println("ArduPilot Airspeed library test");
airspeed.init(hal.analogin->channel(0)); airspeed.init(hal.analogin->channel(0));

View File

@ -55,9 +55,9 @@ void loop()
if (gps->new_data) { if (gps->new_data) {
if (gps->fix) { if (gps->fix) {
hal.console->print("Lat: "); hal.console->print("Lat: ");
print_latlon(hal.uart0,gps->latitude); print_latlon(hal.console,gps->latitude);
hal.console->print(" Lon: "); hal.console->print(" Lon: ");
print_latlon(hal.uart0,gps->longitude); print_latlon(hal.console,gps->longitude);
hal.console->printf(" Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %lu STATUS: %u\n", hal.console->printf(" Alt: %.2fm GSP: %.2fm/s CoG: %d SAT: %d TIM: %lu STATUS: %u\n",
(float)gps->altitude / 100.0, (float)gps->altitude / 100.0,
(float)gps->ground_speed / 100.0, (float)gps->ground_speed / 100.0,

View File

@ -35,7 +35,7 @@ extern const AP_HAL::HAL& hal;
#define DF_CHIP_ERASE_3 0x9A #define DF_CHIP_ERASE_3 0x9A
#ifdef DEBUG #ifdef DEBUG
#define LOGD(format, ...) do { hal.uart0->printf_P(PSTR("DBG/Dataflash: "format), __VA_ARGS__); } while (0) #define LOGD(format, ...) do { hal.console->printf_P(PSTR("DBG/Dataflash: "format), __VA_ARGS__); } while (0)
#else #else
#define LOGD(format, ...) do {} while(0) #define LOGD(format, ...) do {} while(0)
#endif #endif

View File

@ -97,7 +97,7 @@ void setup(void)
hal.console->backend_write((const uint8_t*)hello, strlen(hello)); hal.console->backend_write((const uint8_t*)hello, strlen(hello));
hal.console->println("loopback for 10sec:"); hal.console->println("loopback for 10sec:");
stream_console_loopback(hal.uart0, hal.console, 10000); stream_console_loopback(hal.console, hal.console, 10000);
hal.console->println("loopback done"); hal.console->println("loopback done");
hal.console->backend_close(); hal.console->backend_close();

View File

@ -41,9 +41,9 @@ void loop(void)
// //
// Perform a simple loopback operation. // Perform a simple loopback operation.
// //
c = hal.uart0->read(); c = hal.console->read();
if (-1 != c) if (-1 != c)
hal.uart0->write(c); hal.console->write(c);
} }