mirror of https://github.com/ArduPilot/ardupilot
Plane: enable fixed wing autotune switch
This commit is contained in:
parent
168eb91ed3
commit
845e2ab888
|
@ -161,6 +161,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
|
||||||
case AUX_FUNC::LANDING_FLARE:
|
case AUX_FUNC::LANDING_FLARE:
|
||||||
case AUX_FUNC::PARACHUTE_RELEASE:
|
case AUX_FUNC::PARACHUTE_RELEASE:
|
||||||
case AUX_FUNC::MODE_SWITCH_RESET:
|
case AUX_FUNC::MODE_SWITCH_RESET:
|
||||||
|
case AUX_FUNC::FW_AUTOTUNE:
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::Q_ASSIST:
|
case AUX_FUNC::Q_ASSIST:
|
||||||
|
@ -318,6 +319,10 @@ case AUX_FUNC::ARSPD_CALIBRATE:
|
||||||
plane.reset_control_switch();
|
plane.reset_control_switch();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case AUX_FUNC::FW_AUTOTUNE:
|
||||||
|
plane.autotune_enable(ch_flag == AuxSwitchPos::HIGH);
|
||||||
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
return RC_Channel::do_aux_function(ch_option, ch_flag);
|
return RC_Channel::do_aux_function(ch_option, ch_flag);
|
||||||
}
|
}
|
||||||
|
|
|
@ -148,6 +148,7 @@ void Plane::reset_control_switch()
|
||||||
*/
|
*/
|
||||||
void Plane::autotune_start(void)
|
void Plane::autotune_start(void)
|
||||||
{
|
{
|
||||||
|
gcs().send_text(MAV_SEVERITY_INFO, "Started autotune");
|
||||||
rollController.autotune_start();
|
rollController.autotune_start();
|
||||||
pitchController.autotune_start();
|
pitchController.autotune_start();
|
||||||
}
|
}
|
||||||
|
@ -159,6 +160,7 @@ void Plane::autotune_restore(void)
|
||||||
{
|
{
|
||||||
rollController.autotune_restore();
|
rollController.autotune_restore();
|
||||||
pitchController.autotune_restore();
|
pitchController.autotune_restore();
|
||||||
|
gcs().send_text(MAV_SEVERITY_INFO, "Stopped autotune");
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
Loading…
Reference in New Issue