mirror of https://github.com/ArduPilot/ardupilot
Sub: convert to PWM min and max in AP_Motors
This commit is contained in:
parent
aed79bee6f
commit
672da4e3f2
|
@ -52,6 +52,7 @@ void Sub::init_rc_out()
|
|||
motors.set_update_rate(g.rc_speed);
|
||||
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.convert_pwm_min_max_param(channel_throttle->get_radio_min(), channel_throttle->get_radio_max());
|
||||
motors.update_throttle_range();
|
||||
|
||||
// enable output to motors
|
||||
|
|
Loading…
Reference in New Issue