mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 15:38:29 -04:00
Copter: remove unneeded set_range calls on RC Aux channels
This isn't an exhaustive list of channels used for auxillary input, so that makes this wrong. RC_Channel goes off the raw get_radio_in values, so setting these is a pointless and potentially confusing state change. Also, Plane and Rover don't do this - so things are more consistent after this.
This commit is contained in:
parent
af08379d1b
commit
d5b1f1651e
@ -31,12 +31,6 @@ void Copter::init_rc_in()
|
||||
channel_yaw->set_angle(ROLL_PITCH_YAW_INPUT_MAX);
|
||||
channel_throttle->set_range(1000);
|
||||
|
||||
// set auxiliary servo ranges
|
||||
rc().channel(CH_5)->set_range(1000);
|
||||
rc().channel(CH_6)->set_range(1000);
|
||||
rc().channel(CH_7)->set_range(1000);
|
||||
rc().channel(CH_8)->set_range(1000);
|
||||
|
||||
// set default dead zones
|
||||
default_dead_zones();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user