mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
TradHeli - added TUNE value 13 to allow adjusting of external gyro gain using channel 6
This commit is contained in:
parent
ea66c74ff0
commit
c253996ea9
@ -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
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -147,6 +147,7 @@
|
||||
|
||||
#define CH6_NAV_P 11
|
||||
#define CH6_LOITER_P 12
|
||||
#define CH6_HELI_EXTERNAL_GYRO 13
|
||||
|
||||
// nav byte mask
|
||||
// -------------
|
||||
|
Loading…
Reference in New Issue
Block a user