Browse Source

Plane: reload airspeed after VTOL landing

mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
00c2b4b30f
  1. 2
      ArduPlane/quadplane.cpp
  2. 3
      ArduPlane/system.cpp

2
ArduPlane/quadplane.cpp

@ -1340,6 +1340,8 @@ void QuadPlane::check_land_complete(void) @@ -1340,6 +1340,8 @@ void QuadPlane::check_land_complete(void)
plane.disarm_motors();
land_state = QLAND_COMPLETE;
plane.gcs_send_text(MAV_SEVERITY_INFO,"Land complete");
// reload target airspeed which could have been modified by the mission
plane.g.airspeed_cruise_cm.load();
}
}

3
ArduPlane/system.cpp

@ -840,5 +840,8 @@ bool Plane::disarm_motors(void) @@ -840,5 +840,8 @@ bool Plane::disarm_motors(void)
//only log if disarming was successful
change_arm_state();
// reload target airspeed which could have been modified by a mission
plane.g.airspeed_cruise_cm.load();
return true;
}

Loading…
Cancel
Save