Browse Source

Plane: only send GPS2_RAW when we have a 2nd GPS

master
Andrew Tridgell 11 years ago
parent
commit
e784c81f3e
  1. 2
      ArduPlane/GCS_Mavlink.pde

2
ArduPlane/GCS_Mavlink.pde

@ -301,7 +301,7 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan) @@ -301,7 +301,7 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
g_gps->ground_course_cd, // 1/100 degrees,
g_gps->num_sats);
#if GPS2_ENABLE
if (g_gps2 != NULL) {
if (g_gps2 != NULL && g_gps2->status() != GPS::NO_GPS) {
int16_t payload_space = comm_get_txspace(chan) - MAVLINK_NUM_NON_PAYLOAD_BYTES;
if (payload_space >= MAVLINK_MSG_ID_GPS2_RAW_LEN) {
mavlink_msg_gps2_raw_send(

Loading…
Cancel
Save