Browse Source

Plane: Add an airspeed limit for quadplane takeoffs

master
Michael du Breuil 6 years ago committed by WickedShell
parent
commit
4f22dff14d
  1. 15
      ArduPlane/quadplane.cpp
  2. 1
      ArduPlane/quadplane.h

15
ArduPlane/quadplane.cpp

@ -452,6 +452,15 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { @@ -452,6 +452,15 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = {
// @User: Advanced
AP_GROUPINFO("TKOFF_FAIL_SCL", 14, QuadPlane, takeoff_failure_scalar, 0),
// @Param: TKOFF_ARSP_LIM
// @DisplayName: Takeoff airspeed limit
// @Description: Airspeed limit during takeoff. If the airspeed exceeds this level the vehicle will switch to QLAND. This is useful for ensuring that you don't takeoff into excessively strong wind. If set to 0 there is no limit on airspeed during takeoff.
// @Units: m/s
// @Range: 0 20
// @Increment: 1
// @User: Advanced
AP_GROUPINFO("TKOFF_ARSP_LIM", 15, QuadPlane, maximum_takeoff_airspeed, 0),
AP_GROUPEND
};
@ -2548,6 +2557,12 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd) @@ -2548,6 +2557,12 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd)
return false;
}
if (is_positive(maximum_takeoff_airspeed) && (plane.airspeed.get_airspeed() > maximum_takeoff_airspeed)) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "Failed to complete takeoff, excessive wind");
plane.set_mode(plane.mode_qland, MODE_REASON_VTOL_FAILED_TAKEOFF);
return false;
}
if (plane.current_loc.alt < plane.next_WP_loc.alt) {
return false;
}

1
ArduPlane/quadplane.h

@ -512,6 +512,7 @@ private: @@ -512,6 +512,7 @@ private:
};
AP_Float takeoff_failure_scalar;
AP_Float maximum_takeoff_airspeed;
uint32_t takeoff_start_time_ms;
uint32_t takeoff_time_limit_ms;

Loading…
Cancel
Save