GCS_MAVLink: pass channel number to AP_GPS on RTCM injection

This commit is contained in:
Andrew Tridgell 2024-02-25 10:01:44 +11:00 committed by Randy Mackay
parent 66ccaee83b
commit 127ea4ab95

View File

@ -4081,7 +4081,7 @@ void GCS_MAVLINK::handle_message(const mavlink_message_t &msg)
case MAVLINK_MSG_ID_GPS_INPUT:
case MAVLINK_MSG_ID_HIL_GPS:
case MAVLINK_MSG_ID_GPS_INJECT_DATA:
AP::gps().handle_msg(msg);
AP::gps().handle_msg(chan, msg);
break;
#endif