mirror of https://github.com/ArduPilot/ardupilot
Sub: update_throttle_range don't set_throttle_range
This commit is contained in:
parent
a8f682e9f6
commit
aed79bee6f
|
@ -269,8 +269,7 @@ void Sub::one_hz_loop()
|
||||||
// make it possible to change ahrs orientation at runtime during initial config
|
// make it possible to change ahrs orientation at runtime during initial config
|
||||||
ahrs.update_orientation();
|
ahrs.update_orientation();
|
||||||
|
|
||||||
// set all throttle channel settings
|
motors.update_throttle_range();
|
||||||
motors.set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// update assigned functions and enable auxiliary servos
|
// update assigned functions and enable auxiliary servos
|
||||||
|
|
|
@ -52,7 +52,7 @@ void Sub::init_rc_out()
|
||||||
motors.set_update_rate(g.rc_speed);
|
motors.set_update_rate(g.rc_speed);
|
||||||
motors.set_loop_rate(scheduler.get_loop_rate_hz());
|
motors.set_loop_rate(scheduler.get_loop_rate_hz());
|
||||||
motors.init((AP_Motors::motor_frame_class)g.frame_configuration.get(), AP_Motors::motor_frame_type::MOTOR_FRAME_TYPE_PLUS);
|
motors.init((AP_Motors::motor_frame_class)g.frame_configuration.get(), AP_Motors::motor_frame_type::MOTOR_FRAME_TYPE_PLUS);
|
||||||
motors.set_throttle_range(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
motors.update_throttle_range();
|
||||||
|
|
||||||
// enable output to motors
|
// enable output to motors
|
||||||
if (arming.rc_calibration_checks(true)) {
|
if (arming.rc_calibration_checks(true)) {
|
||||||
|
|
Loading…
Reference in New Issue