mirror of https://github.com/ArduPilot/ardupilot
separate out automatic reset of modes and radio
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1804 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
ac7c6358e9
commit
de442b7a3c
|
@ -124,7 +124,7 @@ void init_ardupilot()
|
||||||
init_rc_in(); // sets up rc channels from radio
|
init_rc_in(); // sets up rc channels from radio
|
||||||
init_rc_out(); // sets up the timer libs
|
init_rc_out(); // sets up the timer libs
|
||||||
|
|
||||||
#ifdef ALWAYS_RESET_SETTINGS
|
#ifdef ALWAYS_RESET_RADIO_RANGE
|
||||||
{
|
{
|
||||||
RC_Channel *rcp = &g.rc_1;
|
RC_Channel *rcp = &g.rc_1;
|
||||||
for (unsigned char i=0; i<8; i++) {
|
for (unsigned char i=0; i<8; i++) {
|
||||||
|
@ -133,7 +133,9 @@ void init_ardupilot()
|
||||||
rcp[i].save_eeprom();
|
rcp[i].save_eeprom();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef ALWAYS_RESET_MODES
|
||||||
default_flight_modes();
|
default_flight_modes();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue