mirror of https://github.com/ArduPilot/ardupilot
AR_Motors: make SRV_Channels::cork non-static
for symmetry with the push function
This commit is contained in:
parent
d204f22fe0
commit
7eb672984e
|
@ -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;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue