mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: accept set_position_target_global_int with non_INT frames
the old frames are deprecated
This commit is contained in:
parent
3e529a241b
commit
a682d304cf
@ -1387,9 +1387,11 @@ void GCS_MAVLINK_Plane::handle_set_position_target_global_int(const mavlink_mess
|
||||
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;
|
||||
|
Loading…
Reference in New Issue
Block a user