Plane: remove pointless wrappers around gcs functions
This commit is contained in:
parent
5dcf4dfffc
commit
03b71e1123
@ -40,7 +40,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
||||
SCHED_TASK(stabilize, 400, 100),
|
||||
SCHED_TASK(set_servos, 400, 100),
|
||||
SCHED_TASK(read_control_switch, 7, 100),
|
||||
SCHED_TASK(gcs_retry_deferred, 50, 500),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, retry_deferred, 50, 500),
|
||||
SCHED_TASK(update_GPS_50Hz, 50, 300),
|
||||
SCHED_TASK(update_GPS_10Hz, 10, 400),
|
||||
SCHED_TASK(navigate, 10, 150),
|
||||
@ -49,8 +49,8 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
||||
SCHED_TASK(update_alt, 10, 200),
|
||||
SCHED_TASK(adjust_altitude_target, 10, 200),
|
||||
SCHED_TASK(afs_fs_check, 10, 100),
|
||||
SCHED_TASK(gcs_update, 50, 500),
|
||||
SCHED_TASK(gcs_data_stream_send, 50, 500),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, update, 50, 500),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, data_stream_send, 50, 500),
|
||||
SCHED_TASK(update_events, 50, 150),
|
||||
SCHED_TASK_CLASS(AP_BattMonitor, &plane.battery, read, 10, 300),
|
||||
SCHED_TASK_CLASS(AP_Baro, &plane.barometer, accumulate, 50, 150),
|
||||
@ -147,7 +147,7 @@ void Plane::ahrs_update()
|
||||
#if HIL_SUPPORT
|
||||
if (g.hil_mode == 1) {
|
||||
// update hil before AHRS update
|
||||
gcs_update();
|
||||
gcs().update();
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -1467,8 +1467,8 @@ void Plane::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) {
|
||||
@ -1479,22 +1479,6 @@ void Plane::mavlink_delay_cb()
|
||||
DataFlash.EnableWrites(true);
|
||||
}
|
||||
|
||||
/*
|
||||
* send data streams in the given rate range on both links
|
||||
*/
|
||||
void Plane::gcs_data_stream_send(void)
|
||||
{
|
||||
gcs().data_stream_send();
|
||||
}
|
||||
|
||||
/*
|
||||
* look for incoming commands on the GCS links
|
||||
*/
|
||||
void Plane::gcs_update(void)
|
||||
{
|
||||
gcs().update();
|
||||
}
|
||||
|
||||
/*
|
||||
send airspeed calibration data
|
||||
*/
|
||||
@ -1503,14 +1487,6 @@ void Plane::gcs_send_airspeed_calibration(const Vector3f &vg)
|
||||
gcs().send_airspeed_calibration(vg);
|
||||
}
|
||||
|
||||
/**
|
||||
retry any deferred messages
|
||||
*/
|
||||
void Plane::gcs_retry_deferred(void)
|
||||
{
|
||||
gcs().retry_deferred();
|
||||
}
|
||||
|
||||
/*
|
||||
return true if we will accept this packet. Used to implement SYSID_ENFORCE
|
||||
*/
|
||||
|
@ -810,10 +810,7 @@ private:
|
||||
|
||||
void send_aoa_ssa(mavlink_channel_t chan);
|
||||
|
||||
void gcs_data_stream_send(void);
|
||||
void gcs_update(void);
|
||||
void gcs_send_airspeed_calibration(const Vector3f &vg);
|
||||
void gcs_retry_deferred(void);
|
||||
|
||||
void Log_Write_Fast(void);
|
||||
void Log_Write_Attitude(void);
|
||||
|
Loading…
Reference in New Issue
Block a user