Plane: add reverse_thrust option when in landing pattern

This commit is contained in:
Tom Pittenger 2020-09-14 19:27:08 -07:00 committed by Tom Pittenger
parent 043a3ba06e
commit c4ab7caa33
2 changed files with 5 additions and 0 deletions

View File

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

View File

@ -61,6 +61,10 @@ bool Plane::allow_reverse_thrust(void) const
allow |= (g.use_reverse_thrust & USE_REVERSE_THRUST_AUTO_WAYPOINT) &&
(nav_cmd == MAV_CMD_NAV_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;