mirror of https://github.com/ArduPilot/ardupilot
AP_LandingGear: use enum-class for SRV_CHANNEL_LIMIT_TRIM and friends
This commit is contained in:
parent
48def9b8a4
commit
992f216cc5
|
@ -120,7 +120,7 @@ void AP_LandingGear::set_position(LandingGearCommand cmd)
|
|||
void AP_LandingGear::deploy()
|
||||
{
|
||||
// set servo PWM to deployed position
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::SRV_CHANNEL_LIMIT_MAX);
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::Limit::MAX);
|
||||
|
||||
// set deployed flag
|
||||
_deployed = true;
|
||||
|
@ -136,7 +136,7 @@ void AP_LandingGear::deploy()
|
|||
void AP_LandingGear::retract()
|
||||
{
|
||||
// set servo PWM to retracted position
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::SRV_CHANNEL_LIMIT_MIN);
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_landing_gear_control, SRV_Channel::Limit::MIN);
|
||||
|
||||
// reset deployed flag
|
||||
_deployed = false;
|
||||
|
|
Loading…
Reference in New Issue