diff --git a/AntennaTracker/mode_servotest.cpp b/AntennaTracker/mode_servotest.cpp index 06b77a956c..e1f951e523 100644 --- a/AntennaTracker/mode_servotest.cpp +++ b/AntennaTracker/mode_servotest.cpp @@ -30,8 +30,10 @@ bool ModeServoTest::set_servo(uint8_t servo_num, uint16_t pwm) SRV_Channels::constrain_pwm(SRV_Channel::k_tracker_pitch); } + auto &srv = AP::srv(); SRV_Channels::calc_pwm(); SRV_Channels::output_ch_all(); + srv.push(); // return success return true; diff --git a/AntennaTracker/servos.cpp b/AntennaTracker/servos.cpp index 5ca8bc0b54..285c26dd4c 100644 --- a/AntennaTracker/servos.cpp +++ b/AntennaTracker/servos.cpp @@ -7,8 +7,10 @@ // init_servos - initialises the servos void Tracker::init_servos() { + auto &srv = AP::srv(); + // update assigned functions and enable auxiliary servos - AP::srv().enable_aux_servos(); + srv.enable_aux_servos(); SRV_Channels::set_default_function(CH_YAW, SRV_Channel::k_tracker_yaw); SRV_Channels::set_default_function(CH_PITCH, SRV_Channel::k_tracker_pitch); @@ -21,6 +23,7 @@ void Tracker::init_servos() SRV_Channels::calc_pwm(); SRV_Channels::output_ch_all(); + srv.push(); yaw_servo_out_filt.set_cutoff_frequency(SERVO_OUT_FILT_HZ); pitch_servo_out_filt.set_cutoff_frequency(SERVO_OUT_FILT_HZ); diff --git a/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index b2a2de8ca3..518a287e44 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -161,11 +161,14 @@ void Tracker::disarm_servos() */ void Tracker::prepare_servos() { + auto &srv = AP::srv(); + start_time_ms = AP_HAL::millis(); 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(); + srv.push(); } void Tracker::set_mode(Mode &newmode, const ModeReason reason) diff --git a/AntennaTracker/tracking.cpp b/AntennaTracker/tracking.cpp index 8a1240d2ee..a2455b6f0b 100644 --- a/AntennaTracker/tracking.cpp +++ b/AntennaTracker/tracking.cpp @@ -121,8 +121,10 @@ void Tracker::update_tracking(void) } // convert servo_out to radio_out and send to servo + auto &srv = AP::srv(); SRV_Channels::calc_pwm(); SRV_Channels::output_ch_all(); + srv.push(); return; }