mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Rover: use setup_uart()
This commit is contained in:
parent
836b365bc8
commit
35e87fa2ea
@ -135,15 +135,10 @@ static void init_ardupilot()
|
||||
check_usb_mux();
|
||||
|
||||
// we have a 2nd serial port for telemetry
|
||||
hal.uartC->begin(map_baudrate(g.serial1_baud, SERIAL1_BAUD), 128, 128);
|
||||
gcs[1].init(hal.uartC);
|
||||
gcs[1].setup_uart(hal.uartC, map_baudrate(g.serial1_baud, SERIAL1_BAUD), 128, 128);
|
||||
|
||||
#if MAVLINK_COMM_NUM_BUFFERS > 2
|
||||
// we may have a 3rd serial port for telemetry
|
||||
if (hal.uartD != NULL) {
|
||||
hal.uartD->begin(map_baudrate(g.serial2_baud, SERIAL2_BAUD), 128, 128);
|
||||
gcs[2].init(hal.uartD);
|
||||
}
|
||||
gcs[2].setup_uart(hal.uartD, map_baudrate(g.serial2_baud, SERIAL2_BAUD), 128, 128);
|
||||
#endif
|
||||
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
|
Loading…
Reference in New Issue
Block a user