mirror of https://github.com/ArduPilot/ardupilot
SRV_Channel: make SRV_Channels::cork non-static
for symmetry with the push function
This commit is contained in:
parent
7eb672984e
commit
89936bab3d
|
@ -539,8 +539,7 @@ public:
|
|||
return SRV_Channel::Aux_servo_function_t((SRV_Channel::k_motor9+(channel-8)));
|
||||
}
|
||||
|
||||
static void cork();
|
||||
|
||||
void cork();
|
||||
void push();
|
||||
|
||||
// disable PWM output to a set of channels given by a mask. This is used by the AP_BLHeli code
|
||||
|
|
|
@ -545,11 +545,12 @@ void SRV_Channels::zero_rc_outputs()
|
|||
* send an invalid signal to all channels to prevent
|
||||
* undesired/unexpected behavior
|
||||
*/
|
||||
cork();
|
||||
auto &srv = AP::srv();
|
||||
srv.cork();
|
||||
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
|
||||
hal.rcout->write(i, 0);
|
||||
}
|
||||
AP::srv().push();
|
||||
srv.push();
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue