mirror of https://github.com/ArduPilot/ardupilot
Plane: accept MAV_FRAME_GLOBAL for set_position and repositioning
This commit is contained in:
parent
e422f2b2fd
commit
20a20bde65
|
@ -756,7 +756,8 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_packet(const mavlink_command_in
|
|||
else if (packet.frame == MAV_FRAME_GLOBAL_TERRAIN_ALT_INT) {
|
||||
requested_position.terrain_alt = 1;
|
||||
}
|
||||
else if (packet.frame != MAV_FRAME_GLOBAL_INT) {
|
||||
else if (packet.frame != MAV_FRAME_GLOBAL_INT &&
|
||||
packet.frame != MAV_FRAME_GLOBAL) {
|
||||
// not a supported frame
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
|
@ -1295,6 +1296,7 @@ void GCS_MAVLINK_Plane::handleMessage(const mavlink_message_t &msg)
|
|||
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_INT:
|
||||
|
|
Loading…
Reference in New Issue