Tracker: remove pointless wrappers around gcs functions

This commit is contained in:
Peter Barker 2018-11-22 14:27:51 +11:00 committed by Peter Barker
parent 03b71e1123
commit 0aa4c4ed9a
3 changed files with 5 additions and 32 deletions

View File

@ -39,8 +39,8 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
SCHED_TASK(update_compass, 10, 1500),
SCHED_TASK_CLASS(AP_BattMonitor, &tracker.battery, read, 10, 1500),
SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, update, 10, 1500),
SCHED_TASK(gcs_update, 50, 1700),
SCHED_TASK(gcs_data_stream_send, 50, 3000),
SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update, 50, 1700),
SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, data_stream_send, 50, 3000),
SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, accumulate, 50, 900),
SCHED_TASK(ten_hz_logging_loop, 10, 300),
#if LOGGING_ENABLED == ENABLED
@ -48,7 +48,7 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
#endif
SCHED_TASK_CLASS(AP_InertialSensor, &tracker.ins, periodic, 50, 50),
SCHED_TASK_CLASS(AP_Notify, &tracker.notify, update, 50, 100),
SCHED_TASK(gcs_retry_deferred, 50, 1000),
SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, retry_deferred, 50, 1000),
SCHED_TASK(one_second_loop, 1, 3900),
SCHED_TASK(compass_cal_update, 50, 100),
SCHED_TASK(accel_cal_update, 10, 100)

View File

@ -573,8 +573,8 @@ void Tracker::mavlink_delay_cb()
}
if (tnow - last_50hz > 20) {
last_50hz = tnow;
gcs_update();
gcs_data_stream_send();
gcs().update();
gcs().data_stream_send();
notify.update();
}
if (tnow - last_5s > 5000) {
@ -584,30 +584,6 @@ void Tracker::mavlink_delay_cb()
DataFlash.EnableWrites(true);
}
/*
* send data streams in the given rate range on both links
*/
void Tracker::gcs_data_stream_send(void)
{
gcs().data_stream_send();
}
/*
* look for incoming commands on the GCS links
*/
void Tracker::gcs_update(void)
{
gcs().update();
}
/**
retry any deferred messages
*/
void Tracker::gcs_retry_deferred(void)
{
gcs().retry_deferred();
}
/*
set_mode() wrapper for MAVLink SET_MODE
*/

View File

@ -225,9 +225,6 @@ private:
// GCS_Mavlink.cpp
void send_extended_status1(mavlink_channel_t chan);
void send_nav_controller_output(mavlink_channel_t chan);
void gcs_data_stream_send(void);
void gcs_update(void);
void gcs_retry_deferred(void);
// Log.cpp
void Log_Write_Attitude();