Tracker: move try_send_message mission handling up

This commit is contained in:
Peter Barker 2017-07-28 10:37:41 +10:00 committed by Francisco Ferreira
parent 7a72c3b1fb
commit de0c6d7ca5
2 changed files with 0 additions and 11 deletions

View File

@ -109,11 +109,6 @@ void Tracker::send_hwstatus(mavlink_channel_t chan)
0);
}
void Tracker::send_waypoint_request(mavlink_channel_t chan)
{
gcs().chan(chan-MAVLINK_COMM_0).queued_waypoint_send();
}
void Tracker::send_nav_controller_output(mavlink_channel_t chan)
{
float alt_diff = (g.alt_source == ALT_SOURCE_BARO) ? nav_status.alt_difference_baro : nav_status.alt_difference_gps;
@ -215,11 +210,6 @@ bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id)
queued_param_send();
break;
case MSG_NEXT_WAYPOINT:
CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
tracker.send_waypoint_request(chan);
break;
case MSG_AHRS:
CHECK_PAYLOAD_SIZE(AHRS);
send_ahrs(tracker.ahrs);

View File

@ -200,7 +200,6 @@ private:
void send_attitude(mavlink_channel_t chan);
void send_location(mavlink_channel_t chan);
void send_hwstatus(mavlink_channel_t chan);
void send_waypoint_request(mavlink_channel_t chan);
void send_nav_controller_output(mavlink_channel_t chan);
void send_simstate(mavlink_channel_t chan);
void mavlink_check_target(const mavlink_message_t* msg);