Skip to content

Commit

Permalink
ArduPlane: use frame instead of bools for setting alt frame
Browse files Browse the repository at this point in the history
* And switch to mavlink_coordinate_frame_to_location_alt_frame

Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed Oct 28, 2024
1 parent 92693e0 commit 8b15739
Showing 1 changed file with 9 additions and 23 deletions.
32 changes: 9 additions & 23 deletions ArduPlane/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1382,33 +1382,19 @@ void GCS_MAVLINK_Plane::handle_set_position_target_global_int(const mavlink_mess

if (pos_target.type_mask & alt_mask)
{
cmd.content.location.alt = pos_target.alt * 100;
cmd.content.location.relative_alt = false;
cmd.content.location.terrain_alt = false;
switch (pos_target.coordinate_frame)
{
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_INT:
break; //default to MSL altitude
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
cmd.content.location.relative_alt = true;
break;
case MAV_FRAME_GLOBAL_TERRAIN_ALT:
case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
cmd.content.location.relative_alt = true;
cmd.content.location.terrain_alt = true;
break;
default:
gcs().send_text(MAV_SEVERITY_WARNING, "Invalid coord frame in SET_POSTION_TARGET_GLOBAL_INT");
msg_valid = false;
break;
}
const int32_t alt_cm = pos_target.alt * 100;
Location::AltFrame frame;
if (mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)pos_target.coordinate_frame, frame)) {
gcs().send_text(MAV_SEVERITY_WARNING, "Invalid coord frame in SET_POSTION_TARGET_GLOBAL_INT");
msg_valid = false;
} else {
cmd.content.location.set_alt_cm(alt_cm, frame);
}

if (msg_valid) {
handle_change_alt_request(cmd);
}
} // end if alt_mask
}
}

MAV_RESULT GCS_MAVLINK_Plane::handle_command_do_set_mission_current(const mavlink_command_int_t &packet)
Expand Down

0 comments on commit 8b15739

Please sign in to comment.