mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Tracker: remove shims used in scheduler table
This commit is contained in:
parent
72b698bf96
commit
f86d4466bd
@ -37,16 +37,16 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = {
|
|||||||
SCHED_TASK(update_tracking, 50, 1000),
|
SCHED_TASK(update_tracking, 50, 1000),
|
||||||
SCHED_TASK(update_GPS, 10, 4000),
|
SCHED_TASK(update_GPS, 10, 4000),
|
||||||
SCHED_TASK(update_compass, 10, 1500),
|
SCHED_TASK(update_compass, 10, 1500),
|
||||||
SCHED_TASK(update_battery, 10, 1500),
|
SCHED_TASK_CLASS(AP_BattMonitor, &tracker.battery, read, 10, 1500),
|
||||||
SCHED_TASK(update_barometer, 10, 1500),
|
SCHED_TASK(update_barometer, 10, 1500),
|
||||||
SCHED_TASK(gcs_update, 50, 1700),
|
SCHED_TASK(gcs_update, 50, 1700),
|
||||||
SCHED_TASK(gcs_data_stream_send, 50, 3000),
|
SCHED_TASK(gcs_data_stream_send, 50, 3000),
|
||||||
SCHED_TASK(compass_accumulate, 50, 1500),
|
SCHED_TASK(compass_accumulate, 50, 1500),
|
||||||
SCHED_TASK(barometer_accumulate, 50, 900),
|
SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, accumulate, 50, 900),
|
||||||
SCHED_TASK(ten_hz_logging_loop, 10, 300),
|
SCHED_TASK(ten_hz_logging_loop, 10, 300),
|
||||||
SCHED_TASK(dataflash_periodic, 50, 300),
|
SCHED_TASK_CLASS(DataFlash_Class, &tracker.DataFlash, periodic_tasks, 50, 300),
|
||||||
SCHED_TASK(ins_periodic, 50, 50),
|
SCHED_TASK_CLASS(AP_InertialSensor, &tracker.ins, periodic, 50, 50),
|
||||||
SCHED_TASK(update_notify, 50, 100),
|
SCHED_TASK_CLASS(AP_Notify, &tracker.notify, update, 50, 100),
|
||||||
SCHED_TASK(check_usb_mux, 10, 300),
|
SCHED_TASK(check_usb_mux, 10, 300),
|
||||||
SCHED_TASK(gcs_retry_deferred, 50, 1000),
|
SCHED_TASK(gcs_retry_deferred, 50, 1000),
|
||||||
SCHED_TASK(one_second_loop, 1, 3900),
|
SCHED_TASK(one_second_loop, 1, 3900),
|
||||||
@ -82,16 +82,6 @@ void Tracker::loop()
|
|||||||
scheduler.run(19900UL);
|
scheduler.run(19900UL);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Tracker::dataflash_periodic(void)
|
|
||||||
{
|
|
||||||
DataFlash.periodic_tasks();
|
|
||||||
}
|
|
||||||
|
|
||||||
void Tracker::ins_periodic()
|
|
||||||
{
|
|
||||||
ins.periodic();
|
|
||||||
}
|
|
||||||
|
|
||||||
void Tracker::one_second_loop()
|
void Tracker::one_second_loop()
|
||||||
{
|
{
|
||||||
// send a heartbeat
|
// send a heartbeat
|
||||||
|
@ -198,8 +198,6 @@ private:
|
|||||||
static const AP_Param::Info var_info[];
|
static const AP_Param::Info var_info[];
|
||||||
static const struct LogStructure log_structure[];
|
static const struct LogStructure log_structure[];
|
||||||
|
|
||||||
void dataflash_periodic(void);
|
|
||||||
void ins_periodic();
|
|
||||||
void one_second_loop();
|
void one_second_loop();
|
||||||
void ten_hz_logging_loop();
|
void ten_hz_logging_loop();
|
||||||
void send_heartbeat(mavlink_channel_t chan);
|
void send_heartbeat(mavlink_channel_t chan);
|
||||||
@ -226,10 +224,8 @@ private:
|
|||||||
void update_barometer(void);
|
void update_barometer(void);
|
||||||
void update_ahrs();
|
void update_ahrs();
|
||||||
void update_compass(void);
|
void update_compass(void);
|
||||||
void update_battery(void);
|
|
||||||
void compass_accumulate(void);
|
void compass_accumulate(void);
|
||||||
void accel_cal_update(void);
|
void accel_cal_update(void);
|
||||||
void barometer_accumulate(void);
|
|
||||||
void update_GPS(void);
|
void update_GPS(void);
|
||||||
void init_servos();
|
void init_servos();
|
||||||
void update_pitch_servo(float pitch);
|
void update_pitch_servo(float pitch);
|
||||||
@ -241,7 +237,6 @@ private:
|
|||||||
void update_yaw_cr_servo(float yaw);
|
void update_yaw_cr_servo(float yaw);
|
||||||
void update_yaw_onoff_servo(float yaw);
|
void update_yaw_onoff_servo(float yaw);
|
||||||
void init_tracker();
|
void init_tracker();
|
||||||
void update_notify();
|
|
||||||
bool get_home_eeprom(struct Location &loc);
|
bool get_home_eeprom(struct Location &loc);
|
||||||
void set_home_eeprom(struct Location temp);
|
void set_home_eeprom(struct Location temp);
|
||||||
void set_home(struct Location temp);
|
void set_home(struct Location temp);
|
||||||
|
@ -43,11 +43,6 @@ void Tracker::update_compass(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void Tracker::update_battery()
|
|
||||||
{
|
|
||||||
battery.read();
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
if the compass is enabled then try to accumulate a reading
|
if the compass is enabled then try to accumulate a reading
|
||||||
*/
|
*/
|
||||||
@ -58,14 +53,6 @@ void Tracker::compass_accumulate(void)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
try to accumulate a baro reading
|
|
||||||
*/
|
|
||||||
void Tracker::barometer_accumulate(void)
|
|
||||||
{
|
|
||||||
barometer.accumulate();
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
calibrate compass
|
calibrate compass
|
||||||
*/
|
*/
|
||||||
|
@ -122,13 +122,6 @@ void Tracker::init_tracker()
|
|||||||
BoardConfig.init_safety();
|
BoardConfig.init_safety();
|
||||||
}
|
}
|
||||||
|
|
||||||
// updates the status of the notify objects
|
|
||||||
// should be called at 50hz
|
|
||||||
void Tracker::update_notify()
|
|
||||||
{
|
|
||||||
notify.update();
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
fetch HOME from EEPROM
|
fetch HOME from EEPROM
|
||||||
*/
|
*/
|
||||||
|
Loading…
Reference in New Issue
Block a user