mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Copter: Autotune use set_accel_roll, pitch, yaw
This commit is contained in:
parent
196f6cf1b7
commit
7957d5fc19
@ -805,7 +805,7 @@ void Copter::autotune_load_orig_gains()
|
||||
g.pid_rate_roll.kI(orig_roll_ri);
|
||||
g.pid_rate_roll.kD(orig_roll_rd);
|
||||
g.p_stabilize_roll.kP(orig_roll_sp);
|
||||
attitude_control.save_accel_roll_max(orig_roll_accel);
|
||||
attitude_control.set_accel_roll_max(orig_roll_accel);
|
||||
} else {
|
||||
failed = true;
|
||||
}
|
||||
@ -816,7 +816,7 @@ void Copter::autotune_load_orig_gains()
|
||||
g.pid_rate_pitch.kI(orig_pitch_ri);
|
||||
g.pid_rate_pitch.kD(orig_pitch_rd);
|
||||
g.p_stabilize_pitch.kP(orig_pitch_sp);
|
||||
attitude_control.save_accel_pitch_max(orig_pitch_accel);
|
||||
attitude_control.set_accel_pitch_max(orig_pitch_accel);
|
||||
} else {
|
||||
failed = true;
|
||||
}
|
||||
@ -828,7 +828,7 @@ void Copter::autotune_load_orig_gains()
|
||||
g.pid_rate_yaw.kD(orig_yaw_rd);
|
||||
g.pid_rate_yaw.filt_hz(orig_yaw_rLPF);
|
||||
g.p_stabilize_yaw.kP(orig_yaw_sp);
|
||||
attitude_control.save_accel_yaw_max(orig_yaw_accel);
|
||||
attitude_control.set_accel_yaw_max(orig_yaw_accel);
|
||||
} else {
|
||||
failed = true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user