AP_HAL: added hal.rcout->set_output_mode()

This commit is contained in:
Andrew Tridgell 2016-04-13 16:23:11 +10:00
parent a658a78364
commit e24d600e78
1 changed files with 9 additions and 0 deletions

View File

@ -107,4 +107,13 @@ public:
will be used to convert channel writes into a percentage will be used to convert channel writes into a percentage
*/ */
virtual void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) {} 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) {}
}; };