mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AntennaTracker: use enum-class for SRV_CHANNEL_LIMIT_TRIM and friends
This commit is contained in:
parent
4c9c5767ed
commit
ee06faed88
@ -195,8 +195,8 @@ void Tracker::disarm_servos()
|
||||
void Tracker::prepare_servos()
|
||||
{
|
||||
start_time_ms = AP_HAL::millis();
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_tracker_yaw, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_tracker_pitch, SRV_Channel::SRV_CHANNEL_LIMIT_TRIM);
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_tracker_yaw, SRV_Channel::Limit::TRIM);
|
||||
SRV_Channels::set_output_limit(SRV_Channel::k_tracker_pitch, SRV_Channel::Limit::TRIM);
|
||||
SRV_Channels::calc_pwm();
|
||||
SRV_Channels::output_ch_all();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user