Browse Source

TradHeli - added TUNE value 13 to allow adjusting of external gyro gain using channel 6

master
unknown 13 years ago
parent
commit
c253996ea9
  1. 7
      ArduCopter/ArduCopter.pde
  2. 1
      ArduCopter/defines.h

7
ArduCopter/ArduCopter.pde

@ -1339,6 +1339,13 @@ static void tuning(){ @@ -1339,6 +1339,13 @@ static void tuning(){
g.pi_nav_lat.kP(tuning_value);
g.pi_nav_lon.kP(tuning_value);
break;
#if FRAME_CONFIG == HELI_FRAME
case CH6_HELI_EXTERNAL_GYRO:
g.rc_6.set_range(1000,2000);
g.heli_ext_gyro_gain = tuning_value * 1000;
break;
#endif
}
}

1
ArduCopter/defines.h

@ -147,6 +147,7 @@ @@ -147,6 +147,7 @@
#define CH6_NAV_P 11
#define CH6_LOITER_P 12
#define CH6_HELI_EXTERNAL_GYRO 13
// nav byte mask
// -------------

Loading…
Cancel
Save