Browse Source

Plane: add reverse_thrust option when in landing pattern

c415-sdk
Tom Pittenger 4 years ago committed by Tom Pittenger
parent
commit
c4ab7caa33
  1. 1
      ArduPlane/defines.h
  2. 4
      ArduPlane/reverse_thrust.cpp

1
ArduPlane/defines.h

@ -144,6 +144,7 @@ enum {
USE_REVERSE_THRUST_CRUISE = (1<<8), USE_REVERSE_THRUST_CRUISE = (1<<8),
USE_REVERSE_THRUST_FBWB = (1<<9), USE_REVERSE_THRUST_FBWB = (1<<9),
USE_REVERSE_THRUST_GUIDED = (1<<10), USE_REVERSE_THRUST_GUIDED = (1<<10),
USE_REVERSE_THRUST_AUTO_LANDING_PATTERN = (1<<11),
}; };
enum FlightOptions { enum FlightOptions {

4
ArduPlane/reverse_thrust.cpp

@ -61,6 +61,10 @@ bool Plane::allow_reverse_thrust(void) const
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_AUTO_WAYPOINT) && allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_AUTO_WAYPOINT) &&
(nav_cmd == MAV_CMD_NAV_WAYPOINT || (nav_cmd == MAV_CMD_NAV_WAYPOINT ||
nav_cmd == MAV_CMD_NAV_SPLINE_WAYPOINT); nav_cmd == MAV_CMD_NAV_SPLINE_WAYPOINT);
// we are on a landing pattern
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_AUTO_LANDING_PATTERN) &&
mission.get_in_landing_sequence_flag();
} }
break; break;

Loading…
Cancel
Save