mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
ArduCopter: fixed HIL build by removing ability to change _kp and _kp_yaw gains (used for accel and gyro sensor mixing)
This commit is contained in:
parent
48074f4766
commit
670a66667f
@ -2369,14 +2369,16 @@ static void tuning(){
|
||||
g.pid_optflow_pitch.kD(tuning_value);
|
||||
break;
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE // do not allow modifying _kp or _kp_yaw gains in HIL mode
|
||||
case CH6_AHRS_YAW_KP:
|
||||
ahrs._kp_yaw.set(tuning_value);
|
||||
break;
|
||||
|
||||
case CH6_AHRS_KP:
|
||||
ahrs._kp.set(tuning_value);
|
||||
//ahrs.push_gains_to_dmp();
|
||||
break;
|
||||
#endif
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user