AP_Param: use hal.util->set_cmdline_parameters() on SITL on reload_defaults_file()

This allow to pass cmdline parameter to Param on start for each vehicle in the same way as param file
This commit is contained in:
Pierre Kancir 2020-08-23 08:25:40 +02:00 committed by Andrew Tridgell
parent 5b356953ff
commit 420c9c9d36

View File

@ -33,6 +33,9 @@
#include <StorageManager/StorageManager.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <stdio.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <SITL/SITL.h>
#endif
extern const AP_HAL::HAL &hal;
@ -1486,6 +1489,9 @@ void AP_Param::reload_defaults_file(bool last_pass)
}
}
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
hal.util->set_cmdline_parameters();
#endif
}