Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Copter: guided mode fix for landing detector internal error #26866

Merged
merged 2 commits into from
Apr 23, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions ArduCopter/mode_guided.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -960,8 +960,8 @@ void ModeGuided::angle_control_run()
}

// TODO: use get_alt_hold_state
// landed with positive desired climb rate, takeoff
if (copter.ap.land_complete && (guided_angle_state.climb_rate_cms > 0.0f)) {
// landed with positive desired climb rate or thrust, takeoff
if (copter.ap.land_complete && positive_thrust_or_climbrate) {
zero_throttle_and_relax_ac();
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
if (motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) {
Expand Down
1 change: 0 additions & 1 deletion Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -11020,7 +11020,6 @@ def disabled_tests(self):
"GroundEffectCompensation_touchDownExpected": "Flapping",
"FlyMissionTwice": "See https://github.com/ArduPilot/ardupilot/pull/18561",
"GPSForYawCompassLearn": "Vehicle currently crashed in spectacular fashion",
"GuidedModeThrust": "land detector raises internal error as we're not saying we're about to take off but just did",
"CompassMot": "Cuases an arithmetic exception in the EKF",
}

Expand Down
Loading