mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Plane: tailsitters in Qassist inherit motor state
This commit is contained in:
parent
d0e885764d
commit
b61cf72b8c
@ -86,3 +86,17 @@ bool Mode::enter()
|
|||||||
return enter_result;
|
return enter_result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool Mode::is_vtol_man_throttle() const
|
||||||
|
{
|
||||||
|
if (!plane.quadplane.in_vtol_mode() &&
|
||||||
|
plane.quadplane.is_tailsitter() &&
|
||||||
|
plane.quadplane.tailsitter_transition_fw_complete() &&
|
||||||
|
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
|
||||||
|
// 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'
|
||||||
|
return !plane.auto_throttle_mode;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
@ -71,7 +71,7 @@ public:
|
|||||||
|
|
||||||
// true for all q modes
|
// true for all q modes
|
||||||
virtual bool is_vtol_mode() const { return false; }
|
virtual bool is_vtol_mode() const { return false; }
|
||||||
virtual bool is_vtol_man_throttle() const { return false; }
|
virtual bool is_vtol_man_throttle() const;
|
||||||
virtual bool is_vtol_man_mode() const { return false; }
|
virtual bool is_vtol_man_mode() const { return false; }
|
||||||
// guided or adsb mode
|
// guided or adsb mode
|
||||||
virtual bool is_guided_mode() const { return false; }
|
virtual bool is_guided_mode() const { return false; }
|
||||||
|
Loading…
Reference in New Issue
Block a user