Skip to content

Commit

Permalink
Copter: fix integrator and yaw target handling during spool up/down
Browse files Browse the repository at this point in the history
  • Loading branch information
bnsgeyer committed Nov 22, 2024
1 parent 53cdd66 commit c14d498
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 13 deletions.
6 changes: 2 additions & 4 deletions ArduCopter/mode_acro_heli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,16 +56,14 @@ void ModeAcro_Heli::run()
attitude_control->reset_rate_controller_I_terms_smoothly();
}
break;
case AP_Motors::SpoolState::SPOOLING_UP:
case AP_Motors::SpoolState::THROTTLE_UNLIMITED:
case AP_Motors::SpoolState::SPOOLING_DOWN:
if (copter.ap.land_complete && !motors->using_leaky_integrator()) {
attitude_control->reset_target_and_rate(false);
attitude_control->reset_rate_controller_I_terms_smoothly();
}
break;
case AP_Motors::SpoolState::SPOOLING_UP:
case AP_Motors::SpoolState::SPOOLING_DOWN:
// do nothing
break;
}

if (!motors->has_flybar()){
Expand Down
7 changes: 2 additions & 5 deletions ArduCopter/mode_drift.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,9 @@ void ModeDrift::run()
}
break;

case AP_Motors::SpoolState::SPOOLING_UP:
case AP_Motors::SpoolState::THROTTLE_UNLIMITED:
case AP_Motors::SpoolState::SPOOLING_DOWN:
// clear landing flag above zero throttle
if (!copter.is_tradheli()) {
if (!motors->limit.throttle_lower) {
Expand All @@ -119,11 +121,6 @@ void ModeDrift::run()
}
}
break;

case AP_Motors::SpoolState::SPOOLING_UP:
case AP_Motors::SpoolState::SPOOLING_DOWN:
// do nothing
break;
}

// call attitude controller
Expand Down
6 changes: 2 additions & 4 deletions ArduCopter/mode_stabilize_heli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,16 +63,14 @@ void ModeStabilize_Heli::run()
attitude_control->reset_rate_controller_I_terms_smoothly();
}
break;
case AP_Motors::SpoolState::SPOOLING_UP:
case AP_Motors::SpoolState::THROTTLE_UNLIMITED:
case AP_Motors::SpoolState::SPOOLING_DOWN:
if (copter.ap.land_complete && !motors->using_leaky_integrator()) {
attitude_control->reset_target_and_rate(false);
attitude_control->reset_rate_controller_I_terms_smoothly();
}
break;
case AP_Motors::SpoolState::SPOOLING_UP:
case AP_Motors::SpoolState::SPOOLING_DOWN:
// do nothing
break;
}

// call attitude controller
Expand Down

0 comments on commit c14d498

Please sign in to comment.