GCS_MAVLink: Match handling of MAV_CMD_EXTERNAL_POSITION_ESTIMATE to common MAVLink dialect

This commit is contained in:
Marek S. Lukasiewicz 2024-03-06 18:37:46 +11:00 committed by Andrew Tridgell
parent 07681416f5
commit baf0da74ed
1 changed files with 1 additions and 1 deletions

View File

@ -5069,7 +5069,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_home(const mavlink_command_int_t &
#if AP_AHRS_POSITION_RESET_ENABLED
MAV_RESULT GCS_MAVLINK::handle_command_int_external_position_estimate(const mavlink_command_int_t &packet)
{
if (packet.frame != MAV_FRAME_GLOBAL ||
if ((packet.frame != MAV_FRAME_GLOBAL && packet.frame != MAV_FRAME_GLOBAL_INT) ||
!isnan(packet.z)) {
// we only support global frame without altitude
return MAV_RESULT_DENIED;