mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: force min/max/trim on inputs 1~7
This commit is contained in:
parent
0b0cda02cc
commit
5ea7d3443d
@ -48,9 +48,13 @@ void Sub::init_rc_in()
|
|||||||
=======
|
=======
|
||||||
>>>>>>> Changed to ArduCopter as the base code.
|
>>>>>>> Changed to ArduCopter as the base code.
|
||||||
|
|
||||||
// force throttle trim to 1100
|
for(int i = 0; i < 7; i++) {
|
||||||
channel_throttle->set_radio_trim(1100);
|
RC_Channel *ch = RC_Channel::rc_channel(i);
|
||||||
channel_throttle->save_eeprom();
|
ch->set_radio_max(1900);
|
||||||
|
ch->set_radio_min(1100);
|
||||||
|
ch->set_radio_trim(1500);
|
||||||
|
ch->save_eeprom();
|
||||||
|
}
|
||||||
|
|
||||||
//set auxiliary servo ranges
|
//set auxiliary servo ranges
|
||||||
// g.rc_5.set_range(0,1000);
|
// g.rc_5.set_range(0,1000);
|
||||||
|
Loading…
Reference in New Issue
Block a user