mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Copter: setup pwm esc scaling
This commit is contained in:
parent
008dc91a15
commit
dcdfff66e8
@ -67,6 +67,11 @@ static void init_rc_out()
|
|||||||
if (ap.pre_arm_rc_check) {
|
if (ap.pre_arm_rc_check) {
|
||||||
output_min();
|
output_min();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
|
||||||
|
// take a proportion of speed. Note: this assumes rc_3 is
|
||||||
|
// throttle and should really use rcmap.
|
||||||
|
hal.rcout->set_esc_scaling(g.rc_3.radio_min, g.rc_3.radio_max);
|
||||||
}
|
}
|
||||||
|
|
||||||
// output_min - enable and output lowest possible value to motors
|
// output_min - enable and output lowest possible value to motors
|
||||||
|
Loading…
Reference in New Issue
Block a user