AP_HAL: added set_esc_scaling() RCOutput function

this will be used to scale outputs for uavcan ESCs based on throttle
range
This commit is contained in:
Andrew Tridgell 2014-11-20 18:30:10 +11:00
parent 5a78c584d2
commit e89d380b73
1 changed files with 8 additions and 0 deletions

View File

@ -71,6 +71,14 @@ public:
force the safety switch off, enabling PWM output from the IO board
*/
virtual void force_safety_off(void) {}
/*
setup scaling of ESC output for ESCs that can output a
percentage of power (such as UAVCAN ESCs). The values are in
microseconds, and represent minimum and maximum PWM values which
will be used to convert channel writes into a percentage
*/
virtual void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) {}
};
#endif // __AP_HAL_RC_OUTPUT_H__