diff --git a/libraries/AR_Motors/AP_MotorsUGV.cpp b/libraries/AR_Motors/AP_MotorsUGV.cpp index 70f9754d62..4b63101d5f 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.cpp +++ b/libraries/AR_Motors/AP_MotorsUGV.cpp @@ -340,10 +340,11 @@ void AP_MotorsUGV::output(bool armed, float ground_speed, float dt) output_sail(); // send values to the PWM timers for output + auto &srv = AP::srv(); SRV_Channels::calc_pwm(); - SRV_Channels::cork(); + srv.cork(); SRV_Channels::output_ch_all(); - AP::srv().push(); + srv.push(); } // test steering or throttle output as a percentage of the total (range -100 to +100) @@ -408,10 +409,11 @@ bool AP_MotorsUGV::output_test_pct(motor_test_order motor_seq, float pct) case MOTOR_TEST_LAST: return false; } + auto &srv = AP::srv(); SRV_Channels::calc_pwm(); - SRV_Channels::cork(); + srv.cork(); SRV_Channels::output_ch_all(); - AP::srv().push(); + srv.push(); return true; } @@ -474,10 +476,11 @@ bool AP_MotorsUGV::output_test_pwm(motor_test_order motor_seq, float pwm) default: return false; } + auto &srv = AP::srv(); SRV_Channels::calc_pwm(); - SRV_Channels::cork(); + srv.cork(); SRV_Channels::output_ch_all(); - AP::srv().push(); + srv.push(); return true; }