mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_HAL_FLYMAPLE RCOutput.cpp: enable_ch no longer resets servo
FLYMAPLERCOutput::enable_ch incorrectly reset the servo to 0, which caused servo twitching once per second when RC_Channel_aux::enable_aux_servos enabled each channel.
This commit is contained in:
parent
ad4db4de6c
commit
bd768a0c0c
@ -68,14 +68,13 @@ void FLYMAPLERCOutput::enable_ch(uint8_t ch)
|
|||||||
}
|
}
|
||||||
pinMode(pin, PWM);
|
pinMode(pin, PWM);
|
||||||
_set_freq(ch, 50); // Default to 50 Hz
|
_set_freq(ch, 50); // Default to 50 Hz
|
||||||
write(ch, 0);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void FLYMAPLERCOutput::disable_ch(uint8_t ch)
|
void FLYMAPLERCOutput::disable_ch(uint8_t ch)
|
||||||
{
|
{
|
||||||
if (ch >= FLYMAPLE_RC_OUTPUT_NUM_CHANNELS)
|
if (ch >= FLYMAPLE_RC_OUTPUT_NUM_CHANNELS)
|
||||||
return;
|
return;
|
||||||
// TODO
|
// Nothing really to do
|
||||||
}
|
}
|
||||||
|
|
||||||
void FLYMAPLERCOutput::write(uint8_t ch, uint16_t period_us)
|
void FLYMAPLERCOutput::write(uint8_t ch, uint16_t period_us)
|
||||||
|
Loading…
Reference in New Issue
Block a user