|
|
@ -870,25 +870,27 @@ void Plane::update_alt() |
|
|
|
|
|
|
|
|
|
|
|
update_flight_stage(); |
|
|
|
update_flight_stage(); |
|
|
|
|
|
|
|
|
|
|
|
bool is_doing_auto_land = (control_mode == AUTO) && (mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND); |
|
|
|
|
|
|
|
float distance_beyond_land_wp = 0; |
|
|
|
|
|
|
|
if (is_doing_auto_land && location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) { |
|
|
|
|
|
|
|
distance_beyond_land_wp = get_distance(current_loc, next_WP_loc); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (auto_throttle_mode && !throttle_suppressed) {
|
|
|
|
if (auto_throttle_mode && !throttle_suppressed) {
|
|
|
|
|
|
|
|
|
|
|
|
// set Flight stage for controller. If not in AUTO then assume normal operation.
|
|
|
|
bool is_doing_auto_land = false; |
|
|
|
// this prevents TECS from being stuck in the wrong stage if you switch from
|
|
|
|
float distance_beyond_land_wp = 0; |
|
|
|
// AUTO to, say, FBWB during an aborted landing
|
|
|
|
|
|
|
|
AP_SpdHgtControl::FlightStage fs = flight_stage; |
|
|
|
switch (flight_stage) { |
|
|
|
if (control_mode != AUTO) { |
|
|
|
case AP_SpdHgtControl::FLIGHT_LAND_APPROACH: |
|
|
|
fs = AP_SpdHgtControl::FLIGHT_NORMAL; |
|
|
|
case AP_SpdHgtControl::FLIGHT_LAND_PREFLARE: |
|
|
|
|
|
|
|
case AP_SpdHgtControl::FLIGHT_LAND_FINAL: |
|
|
|
|
|
|
|
is_doing_auto_land = true; |
|
|
|
|
|
|
|
if (location_passed_point(current_loc, prev_WP_loc, next_WP_loc)) { |
|
|
|
|
|
|
|
distance_beyond_land_wp = get_distance(current_loc, next_WP_loc); |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
break; |
|
|
|
|
|
|
|
default: |
|
|
|
|
|
|
|
break; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
SpdHgt_Controller->update_pitch_throttle(relative_target_altitude_cm(), |
|
|
|
SpdHgt_Controller->update_pitch_throttle(relative_target_altitude_cm(), |
|
|
|
target_airspeed_cm, |
|
|
|
target_airspeed_cm, |
|
|
|
fs, |
|
|
|
flight_stage, |
|
|
|
is_doing_auto_land, |
|
|
|
is_doing_auto_land, |
|
|
|
distance_beyond_land_wp, |
|
|
|
distance_beyond_land_wp, |
|
|
|
auto_state.takeoff_pitch_cd, |
|
|
|
auto_state.takeoff_pitch_cd, |
|
|
@ -940,6 +942,9 @@ void Plane::update_flight_stage(void) |
|
|
|
set_flight_stage(AP_SpdHgtControl::FLIGHT_NORMAL); |
|
|
|
set_flight_stage(AP_SpdHgtControl::FLIGHT_NORMAL); |
|
|
|
} |
|
|
|
} |
|
|
|
} else { |
|
|
|
} else { |
|
|
|
|
|
|
|
// If not in AUTO then assume normal operation for normal TECS operation.
|
|
|
|
|
|
|
|
// This prevents TECS from being stuck in the wrong stage if you switch from
|
|
|
|
|
|
|
|
// AUTO to, say, FBWB during a landing, an aborted landing or takeoff.
|
|
|
|
set_flight_stage(AP_SpdHgtControl::FLIGHT_NORMAL); |
|
|
|
set_flight_stage(AP_SpdHgtControl::FLIGHT_NORMAL); |
|
|
|
} |
|
|
|
} |
|
|
|
} else if (quadplane.in_vtol_mode() || |
|
|
|
} else if (quadplane.in_vtol_mode() || |
|
|
|