mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_HAL_SITL: allow auto-baudrate detection in GPS driver in SITL
this is useful when testing a real GPS in SITL
This commit is contained in:
parent
9500dc6b77
commit
cb60384dc4
@ -84,7 +84,7 @@ void UARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
|
||||
uint16_t port = atoi(args2);
|
||||
_tcp_start_client(args1, port);
|
||||
} else if (strcmp(devtype, "uart") == 0) {
|
||||
uint32_t baudrate = args2? atoi(args2) : 57600;
|
||||
uint32_t baudrate = args2? atoi(args2) : baud;
|
||||
::printf("UART connection %s:%u\n", args1, baudrate);
|
||||
_uart_start_connection(args1, baudrate);
|
||||
} else {
|
||||
|
@ -113,9 +113,13 @@ void SITL_State::_gps_write(const uint8_t *p, uint16_t size)
|
||||
continue;
|
||||
}
|
||||
}
|
||||
write(gps_state.gps_fd, p, 1);
|
||||
if (gps_state.gps_fd != 0) {
|
||||
write(gps_state.gps_fd, p, 1);
|
||||
}
|
||||
if (_sitl->gps2_enable) {
|
||||
write(gps2_state.gps_fd, p, 1);
|
||||
if (gps2_state.gps_fd != 0) {
|
||||
write(gps2_state.gps_fd, p, 1);
|
||||
}
|
||||
}
|
||||
p++;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user