mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_GPS: convert to using hal.serial() instead of hal.uartX
This commit is contained in:
parent
0f5a75f5b9
commit
e02047861a
@ -18,18 +18,18 @@ void setup()
|
|||||||
hal.console->begin(38400);
|
hal.console->begin(38400);
|
||||||
|
|
||||||
// initialise gps uart to 38400 baud
|
// initialise gps uart to 38400 baud
|
||||||
hal.uartB->begin(38400);
|
hal.serial(3)->begin(38400);
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
// send characters received from the console to the GPS
|
// send characters received from the console to the GPS
|
||||||
while (hal.console->available()) {
|
while (hal.console->available()) {
|
||||||
hal.uartB->write(hal.console->read());
|
hal.serial(3)->write(hal.console->read());
|
||||||
}
|
}
|
||||||
// send GPS characters to the console
|
// send GPS characters to the console
|
||||||
while (hal.uartB->available()) {
|
while (hal.serial(3)->available()) {
|
||||||
hal.console->write(hal.uartB->read());
|
hal.console->write(hal.serial(3)->read());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user