mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: use SRV_Channels set_esc_scaling()
this fixes throttle range on Disco with SERVO_RNG_ENABLE=1
This commit is contained in:
parent
2ec439d7e3
commit
57ddc8f58f
@ -39,7 +39,7 @@ void Plane::set_control_channels(void)
|
|||||||
|
|
||||||
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
|
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
|
||||||
// take a proportion of speed
|
// take a proportion of speed
|
||||||
hal.rcout->set_esc_scaling(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
g2.servo_channels.set_esc_scaling(channel_throttle->get_ch_out());
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user