mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: automatically set H_RSC_MIN/MAX from RC8_MIN/MAX on upgrade
This commit is contained in:
parent
1caa2262da
commit
818a5d103f
@ -19,6 +19,19 @@ void Copter::heli_init()
|
||||
// helicopters are always using motor interlock
|
||||
set_using_interlock(true);
|
||||
|
||||
/*
|
||||
automatically set H_RSC_MIN and H_RSC_MAX from RC8_MIN and
|
||||
RC8_MAX so that when users upgrade from tradheli version 3.2 to
|
||||
3.3 they get the same throttle range as in previous versions of
|
||||
the code
|
||||
*/
|
||||
if (!g.heli_servo_rsc.radio_min.load()) {
|
||||
g.heli_servo_rsc.radio_min.set_and_save(g.rc_8.radio_min.get());
|
||||
}
|
||||
if (!g.heli_servo_rsc.radio_max.load()) {
|
||||
g.heli_servo_rsc.radio_max.set_and_save(g.rc_8.radio_max.get());
|
||||
}
|
||||
|
||||
// pre-load stab col values as mode is initialized as Stabilize, but stabilize_init() function is not run on start-up.
|
||||
input_manager.set_use_stab_col(true);
|
||||
input_manager.set_stab_col_ramp(1.0);
|
||||
|
@ -165,6 +165,11 @@ void Copter::init_ardupilot()
|
||||
log_init();
|
||||
#endif
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// trad heli specific initialisation
|
||||
heli_init();
|
||||
#endif
|
||||
|
||||
init_rc_in(); // sets up rc channels from radio
|
||||
init_rc_out(); // sets up motors and output to escs
|
||||
|
||||
@ -251,11 +256,6 @@ void Copter::init_ardupilot()
|
||||
reset_control_switch();
|
||||
init_aux_switches();
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// trad heli specific initialisation
|
||||
heli_init();
|
||||
#endif
|
||||
|
||||
startup_ground(true);
|
||||
|
||||
// we don't want writes to the serial port to cause us to pause
|
||||
|
Loading…
Reference in New Issue
Block a user