mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Rover: remove pointless wrappers around gcs functions
This commit is contained in:
parent
a4243d9c7c
commit
5dcf4dfffc
@ -60,9 +60,9 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||
SCHED_TASK(update_mission, 50, 200),
|
||||
SCHED_TASK(update_logging1, 10, 200),
|
||||
SCHED_TASK(update_logging2, 10, 200),
|
||||
SCHED_TASK(gcs_retry_deferred, 50, 500),
|
||||
SCHED_TASK(gcs_update, 50, 500),
|
||||
SCHED_TASK(gcs_data_stream_send, 50, 1000),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, retry_deferred, 50, 500),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, update, 50, 500),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, data_stream_send, 50, 1000),
|
||||
SCHED_TASK(read_mode_switch, 7, 200),
|
||||
SCHED_TASK(read_aux_all, 10, 200),
|
||||
SCHED_TASK_CLASS(AP_BattMonitor, &rover.battery, read, 10, 300),
|
||||
@ -159,7 +159,7 @@ void Rover::ahrs_update()
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
// update hil before AHRS update
|
||||
gcs_update();
|
||||
gcs().update();
|
||||
#endif
|
||||
|
||||
// AHRS may use movement to calculate heading
|
||||
|
@ -1170,8 +1170,8 @@ void Rover::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) {
|
||||
@ -1182,30 +1182,6 @@ void Rover::mavlink_delay_cb()
|
||||
DataFlash.EnableWrites(true);
|
||||
}
|
||||
|
||||
/*
|
||||
* send data streams in the given rate range on both links
|
||||
*/
|
||||
void Rover::gcs_data_stream_send(void)
|
||||
{
|
||||
gcs().data_stream_send();
|
||||
}
|
||||
|
||||
/*
|
||||
* look for incoming commands on the GCS links
|
||||
*/
|
||||
void Rover::gcs_update(void)
|
||||
{
|
||||
gcs().update();
|
||||
}
|
||||
|
||||
/**
|
||||
retry any deferred messages
|
||||
*/
|
||||
void Rover::gcs_retry_deferred(void)
|
||||
{
|
||||
gcs().retry_deferred();
|
||||
}
|
||||
|
||||
/*
|
||||
return true if we will accept this packet. Used to implement SYSID_ENFORCE
|
||||
*/
|
||||
|
@ -476,9 +476,6 @@ private:
|
||||
void send_pid_tuning(mavlink_channel_t chan);
|
||||
void send_wheel_encoder(mavlink_channel_t chan);
|
||||
void send_fence_status(mavlink_channel_t chan);
|
||||
void gcs_data_stream_send(void);
|
||||
void gcs_update(void);
|
||||
void gcs_retry_deferred(void);
|
||||
|
||||
// Log.cpp
|
||||
void Log_Write_Arm_Disarm();
|
||||
|
Loading…
Reference in New Issue
Block a user