Plane: enable fixed wing autotune switch
This commit is contained in:
parent
71faeb926c
commit
de44dceda4
@ -165,6 +165,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
|
||||
#endif
|
||||
case AUX_FUNC::TRIM_TO_CURRENT_SERVO_RC:
|
||||
case AUX_FUNC::EMERGENCY_LANDING_EN:
|
||||
case AUX_FUNC::FW_AUTOTUNE:
|
||||
break;
|
||||
|
||||
case AUX_FUNC::SOARING:
|
||||
@ -368,6 +369,9 @@ case AUX_FUNC::ARSPD_CALIBRATE:
|
||||
}
|
||||
break;
|
||||
|
||||
case AUX_FUNC::FW_AUTOTUNE:
|
||||
plane.autotune_enable(ch_flag == AuxSwitchPos::HIGH);
|
||||
break;
|
||||
|
||||
default:
|
||||
return RC_Channel::do_aux_function(ch_option, ch_flag);
|
||||
|
@ -161,6 +161,7 @@ void Plane::reset_control_switch()
|
||||
*/
|
||||
void Plane::autotune_start(void)
|
||||
{
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Started autotune");
|
||||
rollController.autotune_start();
|
||||
pitchController.autotune_start();
|
||||
}
|
||||
@ -172,6 +173,7 @@ void Plane::autotune_restore(void)
|
||||
{
|
||||
rollController.autotune_restore();
|
||||
pitchController.autotune_restore();
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Stopped autotune");
|
||||
}
|
||||
|
||||
/*
|
||||
|
Loading…
Reference in New Issue
Block a user