AP_Motors: added get_pwm_type()

This commit is contained in:
Andrew Tridgell 2016-08-29 15:37:44 +10:00
parent 1a3fc56682
commit e9e3a3f491

View File

@ -135,6 +135,9 @@ public:
// set loop rate. Used to support loop rate as a parameter
void set_loop_rate(uint16_t loop_rate) { _loop_rate = loop_rate; }
enum pwm_type { PWM_TYPE_NORMAL=0, PWM_TYPE_ONESHOT=1, PWM_TYPE_ONESHOT125=2 };
pwm_type get_pwm_type(void) const { return (pwm_type)_pwm_type.get(); }
protected:
// output functions that should be overloaded by child classes
virtual void output_armed_stabilizing()=0;
@ -192,6 +195,5 @@ protected:
float _throttle_radio_passthrough = 0.0f; // throttle/collective input from pilot in 0 ~ 1 range. used for setup and providing servo feedback while landed
float _yaw_radio_passthrough = 0.0f; // yaw input from pilot in -1 ~ +1 range. used for setup and providing servo feedback while landed
enum pwm_type { PWM_TYPE_NORMAL=0, PWM_TYPE_ONESHOT=1, PWM_TYPE_ONESHOT125=2 };
AP_Int8 _pwm_type; // PWM output type
};