mirror of https://github.com/ArduPilot/ardupilot
Sub: remove pointless wrappers around gcs functions
This commit is contained in:
parent
ee5339f931
commit
27405f9dd7
|
@ -38,10 +38,10 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
|||
SCHED_TASK_CLASS(AP_Baro, &sub.barometer, accumulate, 50, 90),
|
||||
SCHED_TASK_CLASS(AP_Notify, &sub.notify, update, 50, 90),
|
||||
SCHED_TASK(one_hz_loop, 1, 100),
|
||||
SCHED_TASK(gcs_update, 400, 180),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update, 400, 180),
|
||||
SCHED_TASK(gcs_send_heartbeat, 1, 110),
|
||||
SCHED_TASK(gcs_send_deferred, 50, 550),
|
||||
SCHED_TASK(gcs_data_stream_send, 50, 550),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, retry_deferred, 50, 550),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, data_stream_send, 50, 550),
|
||||
#if MOUNT == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Mount, &sub.camera_mount, update, 50, 75),
|
||||
#endif
|
||||
|
|
|
@ -10,11 +10,6 @@ void Sub::gcs_send_heartbeat()
|
|||
gcs().send_message(MSG_HEARTBEAT);
|
||||
}
|
||||
|
||||
void Sub::gcs_send_deferred()
|
||||
{
|
||||
gcs().retry_deferred();
|
||||
}
|
||||
|
||||
/*
|
||||
* !!NOTE!!
|
||||
*
|
||||
|
@ -1145,9 +1140,9 @@ void Sub::mavlink_delay_cb()
|
|||
}
|
||||
if (tnow - last_50hz > 20) {
|
||||
last_50hz = tnow;
|
||||
gcs_update();
|
||||
gcs_data_stream_send();
|
||||
gcs_send_deferred();
|
||||
gcs().update();
|
||||
gcs().data_stream_send();
|
||||
gcs().retry_deferred();
|
||||
notify.update();
|
||||
}
|
||||
if (tnow - last_5s > 5000) {
|
||||
|
@ -1158,22 +1153,6 @@ void Sub::mavlink_delay_cb()
|
|||
DataFlash.EnableWrites(true);
|
||||
}
|
||||
|
||||
/*
|
||||
* send data streams in the given rate range on both links
|
||||
*/
|
||||
void Sub::gcs_data_stream_send()
|
||||
{
|
||||
gcs().data_stream_send();
|
||||
}
|
||||
|
||||
/*
|
||||
* look for incoming commands on the GCS links
|
||||
*/
|
||||
void Sub::gcs_update()
|
||||
{
|
||||
gcs().update();
|
||||
}
|
||||
|
||||
AP_Mission *GCS_MAVLINK_Sub::get_mission()
|
||||
{
|
||||
return &sub.mission;
|
||||
|
|
|
@ -474,7 +474,6 @@ private:
|
|||
void update_poscon_alt_max();
|
||||
void rotate_body_frame_to_NE(float &x, float &y);
|
||||
void gcs_send_heartbeat(void);
|
||||
void gcs_send_deferred(void);
|
||||
void send_heartbeat(mavlink_channel_t chan);
|
||||
void send_extended_status1(mavlink_channel_t chan);
|
||||
void send_nav_controller_output(mavlink_channel_t chan);
|
||||
|
@ -483,8 +482,6 @@ private:
|
|||
void rpm_update();
|
||||
#endif
|
||||
void send_pid_tuning(mavlink_channel_t chan);
|
||||
void gcs_data_stream_send(void);
|
||||
void gcs_update(void);
|
||||
void Log_Write_Control_Tuning();
|
||||
void Log_Write_Performance();
|
||||
void Log_Write_Attitude();
|
||||
|
|
Loading…
Reference in New Issue