mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
HAL_ChibiOS: added scale_esc_to_unity()
needed for per-motor compass cal
This commit is contained in:
parent
21d401e844
commit
0cf104f2f3
@ -38,6 +38,10 @@ public:
|
||||
}
|
||||
void set_output_mode(enum output_mode mode) override;
|
||||
|
||||
float scale_esc_to_unity(uint16_t pwm) override {
|
||||
return 2.0 * ((float) pwm - _esc_pwm_min) / (_esc_pwm_max - _esc_pwm_min) - 1.0;
|
||||
}
|
||||
|
||||
void cork(void) override;
|
||||
void push(void) override;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user