Browse Source

AP_HAL_SITL: correct segfault when uartg configured

mission-4.1.18
Peter Barker 7 years ago committed by Andrew Tridgell
parent
commit
e577a5564f
  1. 3
      libraries/AP_HAL_SITL/SITL_State.h
  2. 1
      libraries/AP_HAL_SITL/SITL_cmdline.cpp
  3. 4
      libraries/AP_HAL_SITL/UARTDriver.cpp

3
libraries/AP_HAL_SITL/SITL_State.h

@ -71,13 +71,14 @@ public: @@ -71,13 +71,14 @@ public:
uint16_t current2_pin_value; // pin 14
// paths for UART devices
const char *_uart_path[6] {
const char *_uart_path[7] {
"tcp:0:wait",
"GPS1",
"tcp:2",
"tcp:3",
"GPS2",
"tcp:5",
"tcp:6",
};
private:

1
libraries/AP_HAL_SITL/SITL_cmdline.cpp

@ -294,6 +294,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) @@ -294,6 +294,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
case CMDLINE_UARTD:
case CMDLINE_UARTE:
case CMDLINE_UARTF:
case CMDLINE_UARTG:
_uart_path[opt - CMDLINE_UARTA] = gopt.optarg;
break;
case CMDLINE_RTSCTS:

4
libraries/AP_HAL_SITL/UARTDriver.cpp

@ -50,6 +50,10 @@ bool UARTDriver::_console; @@ -50,6 +50,10 @@ bool UARTDriver::_console;
void UARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
{
if (_portNumber > ARRAY_SIZE(_sitlState->_uart_path)) {
AP_HAL::panic("port number out of range; you may need to extend _sitlState->_uart_path");
}
const char *path = _sitlState->_uart_path[_portNumber];
// default to 1MBit

Loading…
Cancel
Save