Plane: quadplane: add allow_weathervane transtion class method

This commit is contained in:
Peter Hall 2022-01-23 22:26:32 +00:00 committed by Andrew Tridgell
parent 6a719664d3
commit 717b18a680
4 changed files with 11 additions and 0 deletions

View File

@ -3259,6 +3259,7 @@ float QuadPlane::get_weathervane_yaw_rate_cds(void)
position control.
*/
if (!in_vtol_mode() ||
!transition->allow_weathervane() ||
!motors->armed() || (motors->get_desired_spool_state() != AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED) ||
plane.control_mode == &plane.mode_qstabilize ||
#if QAUTOTUNE_ENABLED

View File

@ -960,4 +960,10 @@ MAV_VTOL_STATE Tailsitter_Transition::get_mav_vtol_state() const
return MAV_VTOL_STATE_UNDEFINED;
}
// only allow to weathervane once transition is complete and desired pitch has been reached
bool Tailsitter_Transition::allow_weathervane()
{
return !tailsitter.in_vtol_transition() && (vtol_limit_start_ms == 0);
}
#endif // HAL_QUADPLANE_ENABLED

View File

@ -163,6 +163,8 @@ public:
bool set_VTOL_roll_pitch_limit(int32_t& nav_roll_cd, int32_t& nav_pitch_cd) override;
bool allow_weathervane() override;
private:
enum {

View File

@ -52,6 +52,8 @@ public:
virtual bool set_VTOL_roll_pitch_limit(int32_t& nav_roll_cd, int32_t& nav_pitch_cd) { return false; }
virtual bool allow_weathervane() { return true; }
protected:
// refences for convenience