Browse Source

AP_HAL: added hal.rcout->set_output_mode()

master
Andrew Tridgell 9 years ago
parent
commit
e24d600e78
  1. 9
      libraries/AP_HAL/RCOutput.h

9
libraries/AP_HAL/RCOutput.h

@ -107,4 +107,13 @@ public: @@ -107,4 +107,13 @@ public:
will be used to convert channel writes into a percentage
*/
virtual void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) {}
/*
output modes. Allows for support of oneshot
*/
enum output_mode {
MODE_PWM_NORMAL,
MODE_PWM_ONESHOT
};
virtual void set_output_mode(enum output_mode mode) {}
};

Loading…
Cancel
Save