AP_Camera: use location methods to convert altitudes

This commit is contained in:
Peter Barker 2019-04-01 16:59:18 +11:00 committed by Peter Barker
parent c590e1f1c5
commit 919dc26ff6

View File

@ -326,13 +326,17 @@ void AP_Camera::send_feedback(mavlink_channel_t chan) const
// completely ignore this failure! AHRS will provide its best guess. // completely ignore this failure! AHRS will provide its best guess.
} }
float altitude, altitude_rel; int32_t altitude = 0;
if (current_loc.relative_alt) { if (!current_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, altitude)) {
altitude = current_loc.alt+ahrs.get_home().alt; // completely ignore this failure! this is a shouldn't-happen
altitude_rel = current_loc.alt; // as current_loc should never be in an altitude we can't
} else { // convert.
altitude = current_loc.alt; }
altitude_rel = current_loc.alt - ahrs.get_home().alt; int32_t altitude_rel = 0;
if (!current_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, altitude_rel)) {
// completely ignore this failure! this is a shouldn't-happen
// as current_loc should never be in an altitude we can't
// convert.
} }
mavlink_msg_camera_feedback_send( mavlink_msg_camera_feedback_send(