mirror of https://github.com/ArduPilot/ardupilot
Copter: automatically set H_RSC_MIN/MAX from RC8_MIN/MAX on upgrade
this prevents a problem where the disarm throttle will change after upgrading to 3.4
This commit is contained in:
parent
2ce0f4c171
commit
64a8e66dd7
|
@ -18,6 +18,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.3 to
|
||||
3.4 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());
|
||||
}
|
||||
}
|
||||
|
||||
// get_pilot_desired_collective - converts pilot input (from 0 ~ 1000) to a value that can be fed into the channel_throttle->servo_out function
|
||||
|
|
|
@ -166,6 +166,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
|
||||
|
||||
|
@ -257,11 +262,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