mirror of https://github.com/ArduPilot/ardupilot
Tracker: convert to Hz based task table
This commit is contained in:
parent
7daab1ee62
commit
782ba00d4b
|
@ -21,12 +21,7 @@
|
||||||
|
|
||||||
#include "Tracker.h"
|
#include "Tracker.h"
|
||||||
|
|
||||||
#define SCHED_TASK(func, _interval_ticks, _max_time_micros) {\
|
#define SCHED_TASK(func, _interval_ticks, _max_time_micros) SCHED_TASK_CLASS(Tracker, &tracker, func, _interval_ticks, _max_time_micros)
|
||||||
.function = FUNCTOR_BIND(&tracker, &Tracker::func, void),\
|
|
||||||
AP_SCHEDULER_NAME_INITIALIZER(func)\
|
|
||||||
.interval_ticks = _interval_ticks,\
|
|
||||||
.max_time_micros = _max_time_micros,\
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
scheduler table - all regular tasks apart from the fast_loop()
|
scheduler table - all regular tasks apart from the fast_loop()
|
||||||
|
@ -35,21 +30,21 @@
|
||||||
microseconds)
|
microseconds)
|
||||||
*/
|
*/
|
||||||
const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
|
const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
|
||||||
SCHED_TASK(update_ahrs, 1, 1000),
|
SCHED_TASK(update_ahrs, 50, 1000),
|
||||||
SCHED_TASK(read_radio, 1, 200),
|
SCHED_TASK(read_radio, 50, 200),
|
||||||
SCHED_TASK(update_tracking, 1, 1000),
|
SCHED_TASK(update_tracking, 50, 1000),
|
||||||
SCHED_TASK(update_GPS, 5, 4000),
|
SCHED_TASK(update_GPS, 10, 4000),
|
||||||
SCHED_TASK(update_compass, 5, 1500),
|
SCHED_TASK(update_compass, 10, 1500),
|
||||||
SCHED_TASK(update_barometer, 5, 1500),
|
SCHED_TASK(update_barometer, 10, 1500),
|
||||||
SCHED_TASK(gcs_update, 1, 1700),
|
SCHED_TASK(gcs_update, 50, 1700),
|
||||||
SCHED_TASK(gcs_data_stream_send, 1, 3000),
|
SCHED_TASK(gcs_data_stream_send, 50, 3000),
|
||||||
SCHED_TASK(compass_accumulate, 1, 1500),
|
SCHED_TASK(compass_accumulate, 50, 1500),
|
||||||
SCHED_TASK(barometer_accumulate, 1, 900),
|
SCHED_TASK(barometer_accumulate, 50, 900),
|
||||||
SCHED_TASK(update_notify, 1, 100),
|
SCHED_TASK(update_notify, 50, 100),
|
||||||
SCHED_TASK(check_usb_mux, 5, 300),
|
SCHED_TASK(check_usb_mux, 10, 300),
|
||||||
SCHED_TASK(gcs_retry_deferred, 1, 1000),
|
SCHED_TASK(gcs_retry_deferred, 50, 1000),
|
||||||
SCHED_TASK(one_second_loop, 50, 3900),
|
SCHED_TASK(one_second_loop, 1, 3900),
|
||||||
SCHED_TASK(compass_cal_update, 1, 100),
|
SCHED_TASK(compass_cal_update, 50, 100),
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -88,8 +88,6 @@ public:
|
||||||
void loop() override;
|
void loop() override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const AP_InertialSensor::Sample_rate ins_sample_rate = AP_InertialSensor::RATE_50HZ;
|
|
||||||
|
|
||||||
Parameters g;
|
Parameters g;
|
||||||
|
|
||||||
// main loop scheduler
|
// main loop scheduler
|
||||||
|
|
|
@ -77,7 +77,7 @@ void Tracker::init_tracker()
|
||||||
ahrs.init();
|
ahrs.init();
|
||||||
ahrs.set_fly_forward(false);
|
ahrs.set_fly_forward(false);
|
||||||
|
|
||||||
ins.init(ins_sample_rate);
|
ins.init(scheduler.get_loop_rate_hz());
|
||||||
ahrs.reset();
|
ahrs.reset();
|
||||||
|
|
||||||
init_barometer();
|
init_barometer();
|
||||||
|
|
Loading…
Reference in New Issue