APM_Control: convert LIM_PITCH_MIN/MAX -> PTCH_LIM_MIN/MAX_DEG
This commit is contained in:
parent
a06b2d7328
commit
93c4b75a60
@ -211,7 +211,7 @@ void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg)
|
|||||||
att_limit_deg = aparm.roll_limit_cd * 0.01;
|
att_limit_deg = aparm.roll_limit_cd * 0.01;
|
||||||
break;
|
break;
|
||||||
case AUTOTUNE_PITCH:
|
case AUTOTUNE_PITCH:
|
||||||
att_limit_deg = MIN(abs(aparm.pitch_limit_max_cd),abs(aparm.pitch_limit_min_cd))*0.01;
|
att_limit_deg = MIN(abs(aparm.pitch_limit_max*100),abs(aparm.pitch_limit_min*100))*0.01;
|
||||||
break;
|
break;
|
||||||
case AUTOTUNE_YAW:
|
case AUTOTUNE_YAW:
|
||||||
// arbitrary value for yaw angle
|
// arbitrary value for yaw angle
|
||||||
|
Loading…
Reference in New Issue
Block a user