mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
added ALWAYS_RESET_SETTINGS
git-svn-id: https://arducopter.googlecode.com/svn/trunk@1803 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
9e8ef19150
commit
ac7c6358e9
@ -123,6 +123,20 @@ void init_ardupilot()
|
||||
|
||||
init_rc_in(); // sets up rc channels from radio
|
||||
init_rc_out(); // sets up the timer libs
|
||||
|
||||
#ifdef ALWAYS_RESET_SETTINGS
|
||||
{
|
||||
RC_Channel *rcp = &g.rc_1;
|
||||
for (unsigned char i=0; i<8; i++) {
|
||||
rcp[i].radio_min = 1000;
|
||||
rcp[i].radio_max = 2000;
|
||||
rcp[i].save_eeprom();
|
||||
}
|
||||
}
|
||||
|
||||
default_flight_modes();
|
||||
#endif
|
||||
|
||||
init_camera();
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
adc.Init(); // APM ADC library initialization
|
||||
|
Loading…
Reference in New Issue
Block a user