Browse Source

bad hijacking of GPS_Status

mission-4.1.18
Jason Short 13 years ago
parent
commit
90ee0f7e09
  1. 8
      ArduCopter/GCS_Mavlink.pde

8
ArduCopter/GCS_Mavlink.pde

@ -262,10 +262,10 @@ static void NOINLINE send_gps_status(mavlink_channel_t chan) @@ -262,10 +262,10 @@ static void NOINLINE send_gps_status(mavlink_channel_t chan)
mavlink_msg_gps_status_send(
chan,
g_gps->num_sats,
next_WP.alt,
nav_throttle,
angle_boost,
manual_boost,
NULL,
NULL,
NULL,
NULL,
NULL);
}

Loading…
Cancel
Save