GCS_MAVLink: fixed flymaple build

has dual GPS but no RTK support
This commit is contained in:
Andrew Tridgell 2014-06-30 10:48:34 +10:00
parent fc11deb547
commit bcb3d1af14

View File

@ -944,21 +944,20 @@ bool GCS_MAVLINK::send_gps_raw(AP_GPS &gps)
if (gps.num_sensors() > 1 && gps.status(1) > AP_GPS::NO_GPS) { if (gps.num_sensors() > 1 && gps.status(1) > AP_GPS::NO_GPS) {
int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES; payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
if (payload_space >= MAVLINK_MSG_ID_GPS2_RAW_LEN) { if (payload_space >= MAVLINK_MSG_ID_GPS2_RAW_LEN) {
gps.send_mavlink_gps2_raw(chan); gps.send_mavlink_gps2_raw(chan);
} }
#if GPS_RTK_AVAILABLE #if GPS_RTK_AVAILABLE
if (gps.highest_supported_status(1) > AP_GPS::GPS_OK_FIX_3D) { if (gps.highest_supported_status(1) > AP_GPS::GPS_OK_FIX_3D) {
int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES; payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
if (payload_space >= MAVLINK_MSG_ID_GPS2_RTK_LEN) { if (payload_space >= MAVLINK_MSG_ID_GPS2_RTK_LEN) {
gps.send_mavlink_gps2_rtk(chan); gps.send_mavlink_gps2_rtk(chan);
} }
} }
}
#endif #endif
}
#endif #endif
//TODO: Should check what else managed to get through... //TODO: Should check what else managed to get through...