AP_HAL_PX4: added mask to set_output_mode()

this allows for some groups using dshot and some not
This commit is contained in:
Andrew Tridgell 2018-03-14 17:05:23 +11:00
parent 4fb53d44f3
commit 25cc73c1e7
2 changed files with 2 additions and 2 deletions

View File

@ -598,7 +598,7 @@ bool PX4RCOutput::enable_px4io_sbus_out(uint16_t rate_hz)
/*
setup output mode
*/
void PX4RCOutput::set_output_mode(enum output_mode mode)
void PX4RCOutput::set_output_mode(uint16_t mask, enum output_mode mode)
{
if (_output_mode == mode) {
// no change

View File

@ -35,7 +35,7 @@ public:
void cork();
void push();
void set_output_mode(enum output_mode mode) override;
void set_output_mode(uint16_t mask, enum output_mode mode) override;
void timer_tick(void) override;
bool enable_px4io_sbus_out(uint16_t rate_hz) override;