mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: adjust for rename yaw_initialised -> dcm_yaw_initialised
This commit is contained in:
parent
8daa0a099c
commit
a84fda9b1f
@ -496,7 +496,7 @@ void Plane::do_loiter_to_alt(const AP_Mission::Mission_Command& cmd)
|
||||
/********************************************************************************/
|
||||
bool Plane::verify_takeoff()
|
||||
{
|
||||
if (ahrs.yaw_initialised() && steer_state.hold_course_cd == -1) {
|
||||
if (ahrs.dcm_yaw_initialised() && steer_state.hold_course_cd == -1) {
|
||||
const float min_gps_speed = 5;
|
||||
if (auto_state.takeoff_speed_time_ms == 0 &&
|
||||
gps.status() >= AP_GPS::GPS_OK_FIX_3D &&
|
||||
|
Loading…
Reference in New Issue
Block a user