Copter: remove pointless wrappers around gcs functions
This commit is contained in:
parent
0aa4c4ed9a
commit
ee5339f931
@ -136,10 +136,10 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
||||
SCHED_TASK(gpsglitch_check, 10, 50),
|
||||
SCHED_TASK(landinggear_update, 10, 75),
|
||||
SCHED_TASK(lost_vehicle_check, 10, 50),
|
||||
SCHED_TASK(gcs_update, 400, 180),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&copter._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*)&copter._gcs, retry_deferred, 50, 550),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&copter._gcs, data_stream_send, 50, 550),
|
||||
#if MOUNT == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Mount, &copter.camera_mount, update, 50, 75),
|
||||
#endif
|
||||
@ -564,7 +564,7 @@ void Copter::read_AHRS(void)
|
||||
//-----------------------------------------------
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
// update hil before ahrs update
|
||||
gcs_update();
|
||||
gcs().update();
|
||||
#endif
|
||||
|
||||
// we tell AHRS to skip INS update as we have already done it in fast_loop()
|
||||
|
@ -728,13 +728,10 @@ private:
|
||||
|
||||
// GCS_Mavlink.cpp
|
||||
void gcs_send_heartbeat(void);
|
||||
void gcs_send_deferred(void);
|
||||
void send_fence_status(mavlink_channel_t chan);
|
||||
void send_extended_status1(mavlink_channel_t chan);
|
||||
void send_nav_controller_output(mavlink_channel_t chan);
|
||||
void send_rpm(mavlink_channel_t chan);
|
||||
void gcs_data_stream_send(void);
|
||||
void gcs_update(void);
|
||||
|
||||
// heli.cpp
|
||||
void heli_init();
|
||||
|
@ -7,10 +7,6 @@ void Copter::gcs_send_heartbeat(void)
|
||||
gcs().send_message(MSG_HEARTBEAT);
|
||||
}
|
||||
|
||||
void Copter::gcs_send_deferred(void)
|
||||
{
|
||||
gcs().retry_deferred();
|
||||
}
|
||||
|
||||
/*
|
||||
* !!NOTE!!
|
||||
@ -1437,9 +1433,9 @@ void Copter::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) {
|
||||
@ -1450,22 +1446,6 @@ void Copter::mavlink_delay_cb()
|
||||
DataFlash.EnableWrites(true);
|
||||
}
|
||||
|
||||
/*
|
||||
* send data streams in the given rate range on both links
|
||||
*/
|
||||
void Copter::gcs_data_stream_send(void)
|
||||
{
|
||||
gcs().data_stream_send();
|
||||
}
|
||||
|
||||
/*
|
||||
* look for incoming commands on the GCS links
|
||||
*/
|
||||
void Copter::gcs_update(void)
|
||||
{
|
||||
gcs().update();
|
||||
}
|
||||
|
||||
/*
|
||||
return true if we will accept this packet. Used to implement SYSID_ENFORCE
|
||||
*/
|
||||
|
Loading…
Reference in New Issue
Block a user