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: rewrite_get_alt_above_ground_cm for clarity #13676

Merged
Merged
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
19 changes: 12 additions & 7 deletions ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -508,14 +508,19 @@ void Mode::make_safe_spool_down()
*/
int32_t Mode::get_alt_above_ground_cm(void)
{
int32_t alt_above_ground;
if (!copter.get_rangefinder_height_interpolated_cm(alt_above_ground)) {
bool navigating = pos_control->is_active_xy();
if (!navigating || !copter.current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, alt_above_ground)) {
alt_above_ground = copter.current_loc.alt;
}
int32_t alt_above_ground_cm;
if (copter.get_rangefinder_height_interpolated_cm(alt_above_ground_cm)) {
return alt_above_ground_cm;
}
if (!pos_control->is_active_xy()) {
return copter.current_loc.alt;
}
return alt_above_ground;
if (copter.current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, alt_above_ground_cm)) {
return alt_above_ground_cm;
}

// Assume the Earth is flat:
return copter.current_loc.alt;
}

void Mode::land_run_vertical_control(bool pause_descent)
Expand Down