mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Mount: initialize backends after all mounts were added
This commit is contained in:
parent
88f2f7ccae
commit
af634f0421
@ -470,13 +470,19 @@ void AP_Mount::init()
|
|||||||
|
|
||||||
// init new instance
|
// init new instance
|
||||||
if (_backends[instance] != nullptr) {
|
if (_backends[instance] != nullptr) {
|
||||||
_backends[instance]->init();
|
|
||||||
if (!primary_set) {
|
if (!primary_set) {
|
||||||
_primary = instance;
|
_primary = instance;
|
||||||
primary_set = true;
|
primary_set = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// init each instance, do it after all instances were created, so that they all know things
|
||||||
|
for (uint8_t instance=0; instance<AP_MOUNT_MAX_INSTANCES; instance++) {
|
||||||
|
if (_backends[instance] != nullptr) {
|
||||||
|
_backends[instance]->init();
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// update - give mount opportunity to update servos. should be called at 10hz or higher
|
// update - give mount opportunity to update servos. should be called at 10hz or higher
|
||||||
|
Loading…
Reference in New Issue
Block a user