Browse Source

Plane: added Q_RTL_MODE parameter

used to switch to VTOL landing on RTL
mission-4.1.18
Andrew Tridgell 9 years ago
parent
commit
0fd044c1f7
  1. 6
      ArduPlane/ArduPlane.cpp
  2. 9
      ArduPlane/quadplane.cpp
  3. 3
      ArduPlane/quadplane.h

6
ArduPlane/ArduPlane.cpp

@ -748,7 +748,11 @@ void Plane::update_navigation() @@ -748,7 +748,11 @@ void Plane::update_navigation()
break;
case RTL:
if (g.rtl_autoland == 1 &&
if (quadplane.available() && quadplane.rtl_mode == 1 &&
nav_controller->reached_loiter_target()) {
set_mode(QRTL);
break;
} else if (g.rtl_autoland == 1 &&
!auto_state.checked_for_autoland &&
nav_controller->reached_loiter_target() &&
labs(altitude_error_cm) < 1000) {

9
ArduPlane/quadplane.cpp

@ -263,6 +263,13 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { @@ -263,6 +263,13 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Increment: 1
// @User: Standard
AP_GROUPINFO("RTL_ALT", 35, QuadPlane, qrtl_alt, 15),
// @Param: RTL_MODE
// @DisplayName: VTOL RTL mode
// @Description: If this is set to 1 then an RTL will change to QRTL when the loiter target is reached
// @Values: 0:Disabled,1:Enabled
// @User: Standard
AP_GROUPINFO("RTL_MODE", 36, QuadPlane, rtl_mode, 0),
AP_GROUPEND
};
@ -1375,6 +1382,8 @@ void QuadPlane::init_qrtl(void) @@ -1375,6 +1382,8 @@ void QuadPlane::init_qrtl(void)
plane.do_RTL(plane.home.alt + qrtl_alt*100UL);
plane.prev_WP_loc = plane.current_loc;
land.slow_descent = (plane.current_loc.alt > plane.next_WP_loc.alt);
land.state = QLAND_POSITION1;
land.speed_scale = 0;
}
/*

3
ArduPlane/quadplane.h

@ -199,6 +199,9 @@ private: @@ -199,6 +199,9 @@ private:
AP_Int8 enable;
AP_Int8 transition_pitch_max;
// control if a VTOL RTL will be used
AP_Int8 rtl_mode;
struct {
AP_Float gain;
float integrator;

Loading…
Cancel
Save