diff --git a/ArduCopter/mode_brake.cpp b/ArduCopter/mode_brake.cpp index 550e80dd42..e4ebef37bb 100644 --- a/ArduCopter/mode_brake.cpp +++ b/ArduCopter/mode_brake.cpp @@ -91,7 +91,7 @@ void ModeBrake::run() } else if(countdown<=0){ gcs().send_text(MAV_SEVERITY_INFO," 执行继续任务"); - copter.updownStatus == UpDown_ContinueClimb; + copter.updownStatus = UpDown_ContinueClimb; set_mode(Mode::Number::AUTO, ModeReason::REQUEST_CMD); } } diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index 65973331bd..dbd23ffa63 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -96,7 +96,7 @@ void ModeRTL::run(bool disarm_on_land) } else if(countdown<=0){ gcs().send_text(MAV_SEVERITY_INFO,"开始着陆"); - copter.updownStatus == UpDown_ContinueDescent; + copter.updownStatus = UpDown_ContinueDescent; _state = RTL_Land; } }