Browse Source

Plane: describe flight stages without using specific stage name

master
Tom Pittenger 8 years ago
parent
commit
e709705ab8
  1. 17
      ArduPlane/Attitude.cpp
  2. 2
      ArduPlane/GCS_Mavlink.cpp
  3. 7
      ArduPlane/altitude.cpp
  4. 2
      ArduPlane/geofence.cpp
  5. 87
      ArduPlane/is_flying.cpp
  6. 19
      ArduPlane/servos.cpp

17
ArduPlane/Attitude.cpp

@ -218,17 +218,15 @@ void Plane::stabilize_stick_mixing_fbw()
*/ */
void Plane::stabilize_yaw(float speed_scaler) void Plane::stabilize_yaw(float speed_scaler)
{ {
if (control_mode == AUTO && flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL) { if (landing.is_flaring()) {
// in land final setup for ground steering // in flaring then enable ground steering
steering_control.ground_steering = true; steering_control.ground_steering = true;
} else { } else {
// otherwise use ground steering when no input control and we // otherwise use ground steering when no input control and we
// are below the GROUND_STEER_ALT // are below the GROUND_STEER_ALT
steering_control.ground_steering = (channel_roll->get_control_in() == 0 && steering_control.ground_steering = (channel_roll->get_control_in() == 0 &&
fabsf(relative_altitude()) < g.ground_steer_alt); fabsf(relative_altitude()) < g.ground_steer_alt);
if (control_mode == AUTO && if (landing.is_on_approach()) {
(flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH ||
flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE)) {
// don't use ground steering on landing approach // don't use ground steering on landing approach
steering_control.ground_steering = false; steering_control.ground_steering = false;
} }
@ -237,12 +235,11 @@ void Plane::stabilize_yaw(float speed_scaler)
/* /*
first calculate steering_control.steering for a nose or tail first calculate steering_control.steering for a nose or tail
wheel. wheel. We use "course hold" mode for the rudder when either performing
We use "course hold" mode for the rudder when either in the a flare (when the wings are held level) or when in course hold in
final stage of landing (when the wings are help level) or when FBWA mode (when we are below GROUND_STEER_ALT)
in course hold in FBWA mode (when we are below GROUND_STEER_ALT)
*/ */
if ((control_mode == AUTO && flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL) || if (landing.is_flaring() ||
(steer_state.hold_course_cd != -1 && steering_control.ground_steering)) { (steer_state.hold_course_cd != -1 && steering_control.ground_steering)) {
calc_nav_yaw_course(); calc_nav_yaw_course();
} else if (steering_control.ground_steering) { } else if (steering_control.ground_steering) {

2
ArduPlane/GCS_Mavlink.cpp

@ -1344,8 +1344,6 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
case MAV_CMD_DO_GO_AROUND: case MAV_CMD_DO_GO_AROUND:
result = MAV_RESULT_FAILED; result = MAV_RESULT_FAILED;
//Not allowing go around at FLIGHT_LAND_FINAL stage on purpose --
//if plane is close to the ground a go around could be dangerous.
if (plane.landing.in_progress) { if (plane.landing.in_progress) {
// Initiate an aborted landing. This will trigger a pitch-up and // Initiate an aborted landing. This will trigger a pitch-up and
// climb-out to a safe altitude holding heading then one of the // climb-out to a safe altitude holding heading then one of the

7
ArduPlane/altitude.cpp

@ -29,12 +29,11 @@ void Plane::adjust_altitude_target()
control_mode == CRUISE) { control_mode == CRUISE) {
return; return;
} }
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL) { if (landing.is_flaring()) {
// in land final TECS uses TECS_LAND_SINK as a target sink // during a landing flare, use TECS_LAND_SINK as a target sink
// rate, and ignores the target altitude // rate, and ignores the target altitude
set_target_altitude_location(next_WP_loc); set_target_altitude_location(next_WP_loc);
} else if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH || } else if (landing.is_on_approach()) {
flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE) {
landing.setup_landing_glide_slope(prev_WP_loc, next_WP_loc, current_loc, target_altitude.offset_cm); landing.setup_landing_glide_slope(prev_WP_loc, next_WP_loc, current_loc, target_altitude.offset_cm);
landing.adjust_landing_slope_for_rangefinder_bump(rangefinder_state, prev_WP_loc, next_WP_loc, current_loc, auto_state.wp_distance, target_altitude.offset_cm); landing.adjust_landing_slope_for_rangefinder_bump(rangefinder_state, prev_WP_loc, next_WP_loc, current_loc, auto_state.wp_distance, target_altitude.offset_cm);
} else if (reached_loiter_target()) { } else if (reached_loiter_target()) {

2
ArduPlane/geofence.cpp

@ -310,7 +310,7 @@ void Plane::geofence_check(bool altitude_check_only)
struct Location loc; struct Location loc;
// Never trigger a fence breach in the final stage of landing // Never trigger a fence breach in the final stage of landing
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL || flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE) { if (landing.is_expecting_impact()) {
return; return;
} }

87
ArduPlane/is_flying.cpp

@ -70,6 +70,10 @@ void Plane::update_is_flying_5Hz(void)
crash_state.impact_detected = false; crash_state.impact_detected = false;
} }
if (landing.is_on_approach() && fabsf(auto_state.sink_rate) > 0.2f) {
is_flying_bool = true;
}
switch (flight_stage) switch (flight_stage)
{ {
case AP_Vehicle::FixedWing::FLIGHT_TAKEOFF: case AP_Vehicle::FixedWing::FLIGHT_TAKEOFF:
@ -89,16 +93,6 @@ void Plane::update_is_flying_5Hz(void)
// TODO: detect ground impacts // TODO: detect ground impacts
break; break;
case AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH:
if (fabsf(auto_state.sink_rate) > 0.2f) {
is_flying_bool = true;
}
break;
case AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE:
case AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL:
break;
case AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND: case AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND:
if (auto_state.sink_rate < -0.5f) { if (auto_state.sink_rate < -0.5f) {
// steep climb // steep climb
@ -114,9 +108,7 @@ void Plane::update_is_flying_5Hz(void)
// when disarmed assume not flying and need overwhelming evidence that we ARE flying // when disarmed assume not flying and need overwhelming evidence that we ARE flying
is_flying_bool = airspeed_movement && gps_confirmed_movement; is_flying_bool = airspeed_movement && gps_confirmed_movement;
if ((control_mode == AUTO) && if ((flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF) || landing.is_flaring()) {
((flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF) ||
(flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL)) ) {
is_flying_bool = false; is_flying_bool = false;
} }
} }
@ -205,6 +197,39 @@ void Plane::crash_detection_update(void)
if (!is_flying() && arming.is_armed()) if (!is_flying() && arming.is_armed())
{ {
if (landing.is_expecting_impact()) {
// We should be nice and level-ish in this flight stage. If not, we most
// likely had a crazy landing. Throttle is inhibited already at the flare
// but go ahead and notify GCS and perform any additional post-crash actions.
// Declare a crash if we are oriented more that 60deg in pitch or roll
if (!crash_state.checkedHardLanding && // only check once
been_auto_flying &&
(labs(ahrs.roll_sensor) > 6000 || labs(ahrs.pitch_sensor) > 6000)) {
crashed = true;
crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS;
// did we "crash" within 75m of the landing location? Probably just a hard landing
crashed_near_land_waypoint =
get_distance(current_loc, mission.get_current_nav_cmd().content.location) < 75;
// trigger hard landing event right away, or never again. This inhibits a false hard landing
// event when, for example, a minute after a good landing you pick the plane up and
// this logic is still running and detects the plane is on its side as you carry it.
crash_state.debounce_timer_ms = now_ms + CRASH_DETECTION_DELAY_MS;
}
crash_state.checkedHardLanding = true;
} else if (landing.is_on_approach()) {
// when altitude gets low, we automatically flare so ground crashes
// most likely can not be triggered from here. However,
// a crash into a tree would be caught here.
if (been_auto_flying) {
crashed = true;
crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS;
}
} else {
switch (flight_stage) switch (flight_stage)
{ {
case AP_Vehicle::FixedWing::FLIGHT_TAKEOFF: case AP_Vehicle::FixedWing::FLIGHT_TAKEOFF:
@ -231,44 +256,10 @@ void Plane::crash_detection_update(void)
crashed = false; crashed = false;
break; break;
case AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH:
if (been_auto_flying) {
crashed = true;
crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS;
}
// when altitude gets low, we automatically progress to FLIGHT_LAND_FINAL
// so ground crashes most likely can not be triggered from here. However,
// a crash into a tree would be caught here.
break;
case AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE:
case AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL:
// We should be nice and level-ish in this flight stage. If not, we most
// likely had a crazy landing. Throttle is inhibited already at the flare
// but go ahead and notify GCS and perform any additional post-crash actions.
// Declare a crash if we are oriented more that 60deg in pitch or roll
if (!crash_state.checkedHardLanding && // only check once
been_auto_flying &&
(labs(ahrs.roll_sensor) > 6000 || labs(ahrs.pitch_sensor) > 6000)) {
crashed = true;
crash_state.debounce_time_total_ms = CRASH_DETECTION_DELAY_MS;
// did we "crash" within 75m of the landing location? Probably just a hard landing
crashed_near_land_waypoint =
get_distance(current_loc, mission.get_current_nav_cmd().content.location) < 75;
// trigger hard landing event right away, or never again. This inhibits a false hard landing
// event when, for example, a minute after a good landing you pick the plane up and
// this logic is still running and detects the plane is on its side as you carry it.
crash_state.debounce_timer_ms = now_ms + CRASH_DETECTION_DELAY_MS;
}
crash_state.checkedHardLanding = true;
break;
default: default:
break; break;
} // switch } // switch
}
} else { } else {
crash_state.checkedHardLanding = false; crash_state.checkedHardLanding = false;
} }

19
ArduPlane/servos.cpp

@ -417,18 +417,14 @@ void Plane::set_servos_controlled(void)
min_throttle = 0; min_throttle = 0;
} }
if (control_mode == AUTO) {
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL) {
min_throttle = 0;
}
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) { if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
if(aparm.takeoff_throttle_max != 0) { if(aparm.takeoff_throttle_max != 0) {
max_throttle = aparm.takeoff_throttle_max; max_throttle = aparm.takeoff_throttle_max;
} else { } else {
max_throttle = aparm.throttle_max; max_throttle = aparm.throttle_max;
} }
} } else if (landing.is_flaring()) {
min_throttle = 0;
} }
// apply watt limiter // apply watt limiter
@ -499,6 +495,10 @@ void Plane::set_servos_flaps(void)
auto_flap_percent = g.flap_1_percent; auto_flap_percent = g.flap_1_percent;
} //else flaps stay at default zero deflection } //else flaps stay at default zero deflection
if (landing.in_progress && landing.get_flap_percent() != 0) {
auto_flap_percent = landing.get_flap_percent();
}
/* /*
special flap levels for takeoff and landing. This works special flap levels for takeoff and landing. This works
better than speed based flaps as it leads to less better than speed based flaps as it leads to less
@ -518,13 +518,6 @@ void Plane::set_servos_flaps(void)
auto_flap_percent = g.takeoff_flap_percent; auto_flap_percent = g.takeoff_flap_percent;
} }
break; break;
case AP_Vehicle::FixedWing::FLIGHT_LAND_APPROACH:
case AP_Vehicle::FixedWing::FLIGHT_LAND_PREFLARE:
case AP_Vehicle::FixedWing::FLIGHT_LAND_FINAL:
if (landing.get_flap_percent() != 0) {
auto_flap_percent = landing.get_flap_percent();
}
break;
default: default:
break; break;
} }

Loading…
Cancel
Save