Browse Source

Tracker: move try_send_message mission handling up

master
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
de0c6d7ca5
  1. 10
      AntennaTracker/GCS_Mavlink.cpp
  2. 1
      AntennaTracker/Tracker.h

10
AntennaTracker/GCS_Mavlink.cpp

@ -109,11 +109,6 @@ void Tracker::send_hwstatus(mavlink_channel_t chan) @@ -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) @@ -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);

1
AntennaTracker/Tracker.h

@ -200,7 +200,6 @@ private: @@ -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);

Loading…
Cancel
Save