Arducopter.h - fixed incorrect EEPROM address for cam_mode_ADR (and a few other variables after that)

git-svn-id: https://arducopter.googlecode.com/svn/trunk@886 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
rmackay9@yahoo.com 2010-11-22 15:18:41 +00:00
parent ef6519e406
commit 04364e90c0
1 changed files with 6 additions and 6 deletions

View File

@ -645,12 +645,12 @@ void defaultUserConfig() {
#define ch_yaw_offset_ADR 216
#define ch_aux_offset_ADR 220
#define ch_aux2_offset_ADR 224
#define cam_mode_ADR 226
#define mag_orientation_ADR 228 // reserved for future, 31-10-10, jp
#define mag_declination_ADR 230 // reserved for future, 31-10-10, jp
#define mag_offset_x_ADR 232
#define mag_offset_y_ADR 234
#define mag_offset_z_ADR 236
#define cam_mode_ADR 228
#define mag_orientation_ADR 232 // reserved for future, 31-10-10, jp
#define mag_declination_ADR 236 // reserved for future, 31-10-10, jp
#define mag_offset_x_ADR 240
#define mag_offset_y_ADR 244
#define mag_offset_z_ADR 248
//#define eeprom_counter_ADR 238 // hmm should i move these?!? , 31-10-10, jp