AR_Motors: make SRV_Channels::cork non-static

for symmetry with the push function
This commit is contained in:
Peter Barker 2024-11-13 08:09:59 +11:00 committed by Andrew Tridgell
parent d204f22fe0
commit 7eb672984e
1 changed files with 9 additions and 6 deletions

View File

@ -340,10 +340,11 @@ void AP_MotorsUGV::output(bool armed, float ground_speed, float dt)
output_sail(); output_sail();
// send values to the PWM timers for output // send values to the PWM timers for output
auto &srv = AP::srv();
SRV_Channels::calc_pwm(); SRV_Channels::calc_pwm();
SRV_Channels::cork(); srv.cork();
SRV_Channels::output_ch_all(); 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) // 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: case MOTOR_TEST_LAST:
return false; return false;
} }
auto &srv = AP::srv();
SRV_Channels::calc_pwm(); SRV_Channels::calc_pwm();
SRV_Channels::cork(); srv.cork();
SRV_Channels::output_ch_all(); SRV_Channels::output_ch_all();
AP::srv().push(); srv.push();
return true; return true;
} }
@ -474,10 +476,11 @@ bool AP_MotorsUGV::output_test_pwm(motor_test_order motor_seq, float pwm)
default: default:
return false; return false;
} }
auto &srv = AP::srv();
SRV_Channels::calc_pwm(); SRV_Channels::calc_pwm();
SRV_Channels::cork(); srv.cork();
SRV_Channels::output_ch_all(); SRV_Channels::output_ch_all();
AP::srv().push(); srv.push();
return true; return true;
} }