GCS_MAVLink: Replace hardcoded duplicated end_mavlink_gps*_rtk() function with a flexible one

This commit is contained in:
Dr.-Ing. Amilcar Do Carmo Lucas 2017-06-30 15:46:44 +02:00 committed by Francisco Ferreira
parent 430b863f42
commit 91b6404b13
1 changed files with 2 additions and 2 deletions

View File

@ -2225,7 +2225,7 @@ bool GCS_MAVLINK::try_send_gps_message(const enum ap_message id)
break;
case MSG_GPS_RTK:
CHECK_PAYLOAD_SIZE(GPS_RTK);
gps->send_mavlink_gps_rtk(chan);
gps->send_mavlink_gps_rtk(chan, 0);
ret = true;
break;
case MSG_GPS2_RAW:
@ -2235,7 +2235,7 @@ bool GCS_MAVLINK::try_send_gps_message(const enum ap_message id)
break;
case MSG_GPS2_RTK:
CHECK_PAYLOAD_SIZE(GPS2_RTK);
gps->send_mavlink_gps2_rtk(chan);
gps->send_mavlink_gps_rtk(chan, 1);
ret = true;
break;
default: