mirror of https://github.com/ArduPilot/ardupilot
APM_Control: change LIM_ROLL_CD to ROLL_LIMIT_DEG
This commit is contained in:
parent
badf8fabdd
commit
0430923639
|
@ -208,7 +208,7 @@ void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg)
|
|||
float att_limit_deg = 0;
|
||||
switch (type) {
|
||||
case AUTOTUNE_ROLL:
|
||||
att_limit_deg = aparm.roll_limit_cd * 0.01;
|
||||
att_limit_deg = aparm.roll_limit;
|
||||
break;
|
||||
case AUTOTUNE_PITCH:
|
||||
att_limit_deg = MIN(abs(aparm.pitch_limit_max*100),abs(aparm.pitch_limit_min*100))*0.01;
|
||||
|
|
|
@ -361,7 +361,7 @@ float AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool di
|
|||
if (roll_wrapped > 9000) {
|
||||
roll_wrapped = 18000 - roll_wrapped;
|
||||
}
|
||||
const float roll_limit_margin = MIN(aparm.roll_limit_cd + 500.0, 8500.0);
|
||||
const float roll_limit_margin = MIN(aparm.roll_limit*100 + 500.0, 8500.0);
|
||||
if (roll_wrapped > roll_limit_margin && labs(_ahrs.pitch_sensor) < 7000) {
|
||||
float roll_prop = (roll_wrapped - roll_limit_margin) / (float)(9000 - roll_limit_margin);
|
||||
desired_rate *= (1 - roll_prop);
|
||||
|
|
Loading…
Reference in New Issue