Rover: send gps messages as separate queued messages

This commit is contained in:
Peter Barker 2017-08-08 20:01:35 +10:00 committed by Francisco Ferreira
parent 7aaabea4ea
commit edab526b01

View File

@ -554,7 +554,10 @@ GCS_MAVLINK_Rover::data_stream_send(void)
send_message(MSG_EXTENDED_STATUS1);
send_message(MSG_EXTENDED_STATUS2);
send_message(MSG_CURRENT_WAYPOINT);
send_message(MSG_GPS_RAW); // TODO - remove this message after location message is working
send_message(MSG_GPS_RAW);
send_message(MSG_GPS_RTK);
send_message(MSG_GPS2_RAW);
send_message(MSG_GPS2_RTK);
send_message(MSG_NAV_CONTROLLER_OUTPUT);
}