AP_HAL_SITL: call `_sitl->set_stop_MAVLink_sim_state()` when alocating elrs

This commit is contained in:
Iampete1 2024-04-02 03:12:45 +01:00 committed by Andrew Tridgell
parent 700804a015
commit 64b57de559
1 changed files with 1 additions and 0 deletions

View File

@ -319,6 +319,7 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const
// MAVLink serial ports have begin called several times // MAVLink serial ports have begin called several times
if (elrs == nullptr) { if (elrs == nullptr) {
elrs = new SITL::ELRS(portNumber, this); elrs = new SITL::ELRS(portNumber, this);
_sitl->set_stop_MAVLink_sim_state();
} }
return elrs; return elrs;
} }