Skip to content

Commit

Permalink
Copter: Make use of heading correction on ground selectable for tradheli
Browse files Browse the repository at this point in the history
  • Loading branch information
bnsgeyer committed Nov 25, 2024
1 parent 4785e9e commit c05659a
Show file tree
Hide file tree
Showing 9 changed files with 27 additions and 3 deletions.
4 changes: 3 additions & 1 deletion ArduCopter/mode_acro_heli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,9 @@ void ModeAcro_Heli::run()
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);
if (!motors->using_hdg_error_correction()) {
attitude_control->reset_yaw_target_and_rate(false);
}
attitude_control->reset_rate_controller_I_terms_smoothly();
}
break;
Expand Down
3 changes: 3 additions & 0 deletions ArduCopter/mode_althold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,9 @@ void ModeAltHold::run()
break;

case AltHoldModeState::Landed_Ground_Idle:
if (motors->using_hdg_error_correction()) {
attitude_control->reset_yaw_target_and_rate(false);
}
FALLTHROUGH;

case AltHoldModeState::Landed_Pre_Takeoff:
Expand Down
4 changes: 3 additions & 1 deletion ArduCopter/mode_drift.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,9 @@ void ModeDrift::run()
}
} else {
if (copter.ap.land_complete && !motors->using_leaky_integrator()) {
attitude_control->reset_target_and_rate(false);
if (!motors->using_hdg_error_correction()) {
attitude_control->reset_yaw_target_and_rate(false);
}
attitude_control->reset_rate_controller_I_terms_smoothly();
}
}
Expand Down
3 changes: 3 additions & 0 deletions ArduCopter/mode_flowhold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -288,6 +288,9 @@ void ModeFlowHold::run()
break;

case AltHoldModeState::Landed_Ground_Idle:
if (motors->using_hdg_error_correction()) {
attitude_control->reset_yaw_target_and_rate(false);
}
FALLTHROUGH;

case AltHoldModeState::Landed_Pre_Takeoff:
Expand Down
3 changes: 3 additions & 0 deletions ArduCopter/mode_loiter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,6 +132,9 @@ void ModeLoiter::run()
break;

case AltHoldModeState::Landed_Ground_Idle:
if (motors->using_hdg_error_correction()) {
attitude_control->reset_yaw_target_and_rate(false);
}
FALLTHROUGH;

case AltHoldModeState::Landed_Pre_Takeoff:
Expand Down
3 changes: 3 additions & 0 deletions ArduCopter/mode_poshold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,6 +116,9 @@ void ModePosHold::run()
break;

case AltHoldModeState::Landed_Ground_Idle:
if (motors->using_hdg_error_correction()) {
attitude_control->reset_yaw_target_and_rate(false);
}
init_wind_comp_estimate();
FALLTHROUGH;

Expand Down
3 changes: 3 additions & 0 deletions ArduCopter/mode_sport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,9 @@ void ModeSport::run()
break;

case AltHoldModeState::Landed_Ground_Idle:
if (motors->using_hdg_error_correction()) {
attitude_control->reset_yaw_target_and_rate(false);
}
FALLTHROUGH;

case AltHoldModeState::Landed_Pre_Takeoff:
Expand Down
4 changes: 3 additions & 1 deletion ArduCopter/mode_stabilize_heli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,9 @@ void ModeStabilize_Heli::run()
// If aircraft is landed, set target heading to current and reset the integrator
// Otherwise motors could be at ground idle for practice autorotation
if ((motors->init_targets_on_arming() && motors->using_leaky_integrator()) || (copter.ap.land_complete && !motors->using_leaky_integrator())) {
attitude_control->reset_yaw_target_and_rate(false);
if (!motors->using_hdg_error_correction()) {
attitude_control->reset_yaw_target_and_rate(false);
}
attitude_control->reset_rate_controller_I_terms_smoothly();
}
break;
Expand Down
3 changes: 3 additions & 0 deletions ArduCopter/mode_zigzag.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -356,6 +356,9 @@ void ModeZigZag::manual_control()
break;

case AltHoldModeState::Landed_Ground_Idle:
if (motors->using_hdg_error_correction()) {
attitude_control->reset_yaw_target_and_rate(false);
}
FALLTHROUGH;

case AltHoldModeState::Landed_Pre_Takeoff:
Expand Down

0 comments on commit c05659a

Please sign in to comment.