Plane: tailsitter: ask for FW state don't check

This commit is contained in:
Iampete1 2020-10-13 17:59:30 +01:00 committed by Andrew Tridgell
parent 22b8ed5adf
commit e6ba53856a
3 changed files with 16 additions and 7 deletions

View File

@ -88,14 +88,12 @@ bool Mode::enter()
bool Mode::is_vtol_man_throttle() const
{
if (!plane.quadplane.in_vtol_mode() &&
plane.quadplane.is_tailsitter() &&
plane.quadplane.tailsitter_transition_fw_complete() &&
if (plane.quadplane.is_tailsitter_in_fw_flight() &&
plane.quadplane.assisted_flight) {
// a tailsitter that has fully transisisoned to Q-assisted forward flight
// in this case the forward throttle directly drives the vertical throttle
// We are a tailsitter that has fully transitioned to Q-assisted forward flight.
// In this case the forward throttle directly drives the vertical throttle so
// set vertical throttle state to match the forward throttle state. Confusingly the booleans are inverted,
// forward throttle uses 'auto_throttle_mode' whereas vertical used 'is_vtol_man_throttle'
// forward throttle uses 'auto_throttle_mode' whereas vertical uses 'is_vtol_man_throttle'.
return !plane.auto_throttle_mode;
}
return false;

View File

@ -130,6 +130,9 @@ public:
// check if we have completed transition to fixed wing
bool tailsitter_transition_fw_complete(void);
// return true if we are a tailsitter in FW flight
bool is_tailsitter_in_fw_flight(void) const;
// check if we have completed transition to vtol
bool tailsitter_transition_vtol_complete(void) const;

View File

@ -114,7 +114,7 @@ void QuadPlane::tailsitter_output(void)
// handle Copter controller
// the MultiCopter rate controller has already been run in an earlier call
// to motors_output() from quadplane.update(), unless we are in assisted flight
if (assisted_flight && tailsitter_transition_fw_complete()) {
if (assisted_flight && is_tailsitter_in_fw_flight()) {
hold_stabilize(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * 0.01f);
motors_output(true);
@ -267,6 +267,14 @@ bool QuadPlane::in_tailsitter_vtol_transition(void) const
return is_tailsitter() && in_vtol_mode() && transition_state == TRANSITION_ANGLE_WAIT_VTOL;
}
/*
return true if we are a tailsitter in FW flight
*/
bool QuadPlane::is_tailsitter_in_fw_flight(void) const
{
return is_tailsitter() && !in_vtol_mode() && transition_state == TRANSITION_DONE;
}
/*
account for speed scaling of control surfaces in VTOL modes
*/