mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2025-12-10 00:28:42 -06:00
SITL: allow calling of init multiple times
... to allow for esp32 using existing init call and HAL_ChibiOS making the call very early
This commit is contained in:
parent
095877c9ba
commit
456cdadb82
@ -127,6 +127,11 @@ public:
|
|||||||
static SIM *get_singleton() { return _singleton; }
|
static SIM *get_singleton() { return _singleton; }
|
||||||
|
|
||||||
void init() {
|
void init() {
|
||||||
|
if (init_done) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
init_done = true;
|
||||||
|
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
AP_Param::setup_object_defaults(this, var_info2);
|
AP_Param::setup_object_defaults(this, var_info2);
|
||||||
AP_Param::setup_object_defaults(this, var_info3);
|
AP_Param::setup_object_defaults(this, var_info3);
|
||||||
@ -149,6 +154,7 @@ public:
|
|||||||
mag_ofs[i].set(Vector3f(5, 13, -18));
|
mag_ofs[i].set(Vector3f(5, 13, -18));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
bool init_done;
|
||||||
|
|
||||||
enum SITL_RCFail {
|
enum SITL_RCFail {
|
||||||
SITL_RCFail_None = 0,
|
SITL_RCFail_None = 0,
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user