mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
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:
parent
5b356953ff
commit
420c9c9d36
@ -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
|
||||
}
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user