Browse Source

Plane: log start of quadplane transition

master
Andrew Tridgell 9 years ago
parent
commit
19834c12e2
  1. 3
      ArduPlane/quadplane.cpp

3
ArduPlane/quadplane.cpp

@ -888,6 +888,9 @@ void QuadPlane::update_transition(void)
plane.channel_throttle->get_control_in()>0 || plane.channel_throttle->get_control_in()>0 ||
plane.is_flying())) { plane.is_flying())) {
// the quad should provide some assistance to the plane // the quad should provide some assistance to the plane
if (transition_state != TRANSITION_AIRSPEED_WAIT) {
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Transition started airspeed %.1f", aspeed);
}
transition_state = TRANSITION_AIRSPEED_WAIT; transition_state = TRANSITION_AIRSPEED_WAIT;
transition_start_ms = millis(); transition_start_ms = millis();
assisted_flight = true; assisted_flight = true;

Loading…
Cancel
Save