mirror of https://github.com/ArduPilot/ardupilot
Copter: vibration compensation turns off in manual modes
This commit is contained in:
parent
6b790eaca0
commit
4fded652dc
|
@ -262,7 +262,7 @@ void Copter::check_vibration()
|
|||
|
||||
const bool is_vibration_affected = ahrs.is_vibration_affected();
|
||||
const bool bad_vibe_detected = (innovation_checks_valid && innov_velD_posD_positive && (vel_variance > 1.0f)) || is_vibration_affected;
|
||||
const bool do_bad_vibe_actions = (g2.fs_vibe_enabled == 1) && bad_vibe_detected && motors->armed();
|
||||
const bool do_bad_vibe_actions = (g2.fs_vibe_enabled == 1) && bad_vibe_detected && motors->armed() && !flightmode->has_manual_throttle();
|
||||
|
||||
if (!vibration_check.high_vibes) {
|
||||
// initialise timers
|
||||
|
@ -271,7 +271,7 @@ void Copter::check_vibration()
|
|||
}
|
||||
// check if failure has persisted for at least 1 second
|
||||
if (now - vibration_check.start_ms > 1000) {
|
||||
// switch ekf to use resistant gains
|
||||
// switch position controller to use resistant gains
|
||||
vibration_check.clear_ms = 0;
|
||||
vibration_check.high_vibes = true;
|
||||
pos_control->set_vibe_comp(true);
|
||||
|
@ -285,7 +285,7 @@ void Copter::check_vibration()
|
|||
}
|
||||
// turn off vibration compensation after 15 seconds
|
||||
if (now - vibration_check.clear_ms > 15000) {
|
||||
// restore ekf gains, reset timers and update user
|
||||
// restore position controller gains, reset timers and update user
|
||||
vibration_check.start_ms = 0;
|
||||
vibration_check.high_vibes = false;
|
||||
pos_control->set_vibe_comp(false);
|
||||
|
|
Loading…
Reference in New Issue