mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_NavEKF3: fixed multi-core yaw reset
thanks to Alex Burka for finding this
This commit is contained in:
parent
dc32f7a12f
commit
a4716fb9bf
@ -978,7 +978,7 @@ void NavEKF3::checkLaneSwitch(void)
|
|||||||
void NavEKF3::requestYawReset(void)
|
void NavEKF3::requestYawReset(void)
|
||||||
{
|
{
|
||||||
for (uint8_t i = 0; i < num_cores; i++) {
|
for (uint8_t i = 0; i < num_cores; i++) {
|
||||||
core[primary].EKFGSF_requestYawReset();
|
core[i].EKFGSF_requestYawReset();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user