mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_VisualOdom: adjust for rename yaw_initialised -> dcm_yaw_initialised
This commit is contained in:
parent
a84fda9b1f
commit
d2822635ca
@ -135,7 +135,7 @@ bool AP_VisualOdom_IntelT265::align_sensor_to_vehicle(const Vector3f &position,
|
|||||||
}
|
}
|
||||||
|
|
||||||
// do not align until ahrs yaw initialised
|
// do not align until ahrs yaw initialised
|
||||||
if (!AP::ahrs().initialised() || !AP::ahrs().yaw_initialised()) {
|
if (!AP::ahrs().initialised() || !AP::ahrs().dcm_yaw_initialised()) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user