mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
ArduCopter: just call set_throttle_range()
Now set_throttle_range in AP_Motors does the right thing, calling out the RCOutput method.
This commit is contained in:
parent
ade1876318
commit
a589a84e32
@ -53,6 +53,10 @@ void Copter::init_rc_out()
|
|||||||
motors->init((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());
|
motors->init((AP_Motors::motor_frame_class)g2.frame_class.get(), (AP_Motors::motor_frame_type)g.frame_type.get());
|
||||||
#if FRAME_CONFIG != HELI_FRAME
|
#if FRAME_CONFIG != HELI_FRAME
|
||||||
motors->set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
motors->set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
||||||
|
#else
|
||||||
|
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
|
||||||
|
// take a proportion of speed.
|
||||||
|
hal.rcout->set_esc_scaling(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// delay up to 2 second for first radio input
|
// delay up to 2 second for first radio input
|
||||||
@ -62,10 +66,6 @@ void Copter::init_rc_out()
|
|||||||
read_radio();
|
read_radio();
|
||||||
}
|
}
|
||||||
|
|
||||||
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
|
|
||||||
// take a proportion of speed.
|
|
||||||
hal.rcout->set_esc_scaling(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
|
||||||
|
|
||||||
// check if we should enter esc calibration mode
|
// check if we should enter esc calibration mode
|
||||||
esc_calibration_startup_check();
|
esc_calibration_startup_check();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user