Browse Source

Tracker: eliminate gcs_send_message wraper

master
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
7865d467d3
  1. 2
      AntennaTracker/AntennaTracker.cpp
  2. 14
      AntennaTracker/GCS_Mavlink.cpp
  3. 1
      AntennaTracker/Tracker.h

2
AntennaTracker/AntennaTracker.cpp

@ -85,7 +85,7 @@ void Tracker::dataflash_periodic(void) @@ -85,7 +85,7 @@ void Tracker::dataflash_periodic(void)
void Tracker::one_second_loop()
{
// send a heartbeat
gcs_send_message(MSG_HEARTBEAT);
gcs().send_message(MSG_HEARTBEAT);
// make it possible to change orientation at runtime
ahrs.set_orientation();

14
AntennaTracker/GCS_Mavlink.cpp

@ -857,8 +857,8 @@ void Tracker::mavlink_delay_cb() @@ -857,8 +857,8 @@ void Tracker::mavlink_delay_cb()
uint32_t tnow = AP_HAL::millis();
if (tnow - last_1hz > 1000) {
last_1hz = tnow;
gcs_send_message(MSG_HEARTBEAT);
gcs_send_message(MSG_EXTENDED_STATUS1);
gcs().send_message(MSG_HEARTBEAT);
gcs().send_message(MSG_EXTENDED_STATUS1);
}
if (tnow - last_50hz > 20) {
last_50hz = tnow;
@ -874,14 +874,6 @@ void Tracker::mavlink_delay_cb() @@ -874,14 +874,6 @@ void Tracker::mavlink_delay_cb()
tracker.in_mavlink_delay = false;
}
/*
* send a message on both GCS links
*/
void Tracker::gcs_send_message(enum ap_message id)
{
gcs().send_message(id);
}
/*
* send data streams in the given rate range on both links
*/
@ -903,6 +895,6 @@ void Tracker::gcs_update(void) @@ -903,6 +895,6 @@ void Tracker::gcs_update(void)
*/
void Tracker::gcs_retry_deferred(void)
{
gcs_send_message(MSG_RETRY_DEFERRED);
gcs().send_message(MSG_RETRY_DEFERRED);
gcs().service_statustext();
}

1
AntennaTracker/Tracker.h

@ -204,7 +204,6 @@ private: @@ -204,7 +204,6 @@ private:
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);
void gcs_send_message(enum ap_message id);
void gcs_data_stream_send(void);
void gcs_update(void);
void gcs_retry_deferred(void);

Loading…
Cancel
Save