mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 10:08:28 -04:00
Copter: remove setting of heli_servo_rsc pwm range
This object is not used
This commit is contained in:
parent
1f37f5a0e7
commit
ef5dbae707
@ -16,19 +16,6 @@ static int8_t heli_dynamic_flight_counter;
|
|||||||
// heli_init - perform any special initialisation required for the tradheli
|
// heli_init - perform any special initialisation required for the tradheli
|
||||||
void Copter::heli_init()
|
void Copter::heli_init()
|
||||||
{
|
{
|
||||||
/*
|
|
||||||
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.configured()) {
|
|
||||||
g.heli_servo_rsc.radio_min.set_and_save(g.rc_8.radio_min.get());
|
|
||||||
}
|
|
||||||
if (!g.heli_servo_rsc.radio_max.configured()) {
|
|
||||||
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.
|
// 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_use_stab_col(true);
|
||||||
input_manager.set_stab_col_ramp(1.0);
|
input_manager.set_stab_col_ramp(1.0);
|
||||||
|
Loading…
Reference in New Issue
Block a user