Browse Source

Tracker: move sending of simstate up

master
Peter Barker 7 years ago committed by Peter Barker
parent
commit
d705dbcfc1
  1. 13
      AntennaTracker/GCS_Mavlink.cpp
  2. 1
      AntennaTracker/Tracker.h

13
AntennaTracker/GCS_Mavlink.cpp

@ -115,14 +115,6 @@ void Tracker::send_nav_controller_output(mavlink_channel_t chan)
} }
// report simulator state
void Tracker::send_simstate(mavlink_channel_t chan)
{
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
sitl.simstate_send(chan);
#endif
}
bool GCS_MAVLINK_Tracker::handle_guided_request(AP_Mission::Mission_Command&) bool GCS_MAVLINK_Tracker::handle_guided_request(AP_Mission::Mission_Command&)
{ {
// do nothing // do nothing
@ -144,11 +136,6 @@ bool GCS_MAVLINK_Tracker::try_send_message(enum ap_message id)
tracker.send_nav_controller_output(chan); tracker.send_nav_controller_output(chan);
break; break;
case MSG_SIMSTATE:
CHECK_PAYLOAD_SIZE(SIMSTATE);
tracker.send_simstate(chan);
break;
case MSG_EXTENDED_STATUS1: case MSG_EXTENDED_STATUS1:
CHECK_PAYLOAD_SIZE(SYS_STATUS); CHECK_PAYLOAD_SIZE(SYS_STATUS);
tracker.send_extended_status1(chan); tracker.send_extended_status1(chan);

1
AntennaTracker/Tracker.h

@ -201,7 +201,6 @@ private:
void ten_hz_logging_loop(); void ten_hz_logging_loop();
void send_extended_status1(mavlink_channel_t chan); void send_extended_status1(mavlink_channel_t chan);
void send_nav_controller_output(mavlink_channel_t chan); void send_nav_controller_output(mavlink_channel_t chan);
void send_simstate(mavlink_channel_t chan);
void gcs_data_stream_send(void); void gcs_data_stream_send(void);
void gcs_update(void); void gcs_update(void);
void gcs_retry_deferred(void); void gcs_retry_deferred(void);

Loading…
Cancel
Save