mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
Added new gain and clamp value for DCM
This commit is contained in:
parent
fdcf9aecd5
commit
11363a26cb
@ -343,10 +343,11 @@ static void init_ardupilot()
|
||||
reset_control_switch();
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
dcm.kp_roll_pitch(0.030000);
|
||||
dcm.kp_roll_pitch(0.130000);
|
||||
dcm.ki_roll_pitch(0.00001278), // 50 hz I term
|
||||
dcm.kp_yaw(0.08);
|
||||
dcm.ki_yaw(0.00004);
|
||||
dcm._clamp = 5;
|
||||
#endif
|
||||
|
||||
// init the Z damopener
|
||||
|
Loading…
Reference in New Issue
Block a user