Copter: changed to Hz based task table

This commit is contained in:
Andrew Tridgell 2015-12-26 15:00:03 +11:00 committed by Randy Mackay
parent 513d5c17b9
commit 4dd8714880
5 changed files with 47 additions and 56 deletions

View File

@ -75,12 +75,7 @@
#include "Copter.h"
#define SCHED_TASK(func, _interval_ticks, _max_time_micros) {\
.function = FUNCTOR_BIND(&copter, &Copter::func, void),\
AP_SCHEDULER_NAME_INITIALIZER(func)\
.interval_ticks = _interval_ticks,\
.max_time_micros = _max_time_micros,\
}
#define SCHED_TASK(func, rate_hz, max_time_micros) SCHED_TASK_CLASS(Copter, &copter, func, rate_hz, max_time_micros)
/*
scheduler table for fast CPUs - all regular tasks apart from the fast_loop()
@ -99,70 +94,70 @@
*/
const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(rc_loop, 4, 130),
SCHED_TASK(throttle_loop, 8, 75),
SCHED_TASK(update_GPS, 8, 200),
SCHED_TASK(rc_loop, 100, 130),
SCHED_TASK(throttle_loop, 50, 75),
SCHED_TASK(update_GPS, 50, 200),
#if OPTFLOW == ENABLED
SCHED_TASK(update_optical_flow, 2, 160),
SCHED_TASK(update_optical_flow, 200, 160),
#endif
SCHED_TASK(update_batt_compass, 40, 120),
SCHED_TASK(read_aux_switches, 40, 50),
SCHED_TASK(arm_motors_check, 40, 50),
SCHED_TASK(auto_disarm_check, 40, 50),
SCHED_TASK(auto_trim, 40, 75),
SCHED_TASK(update_altitude, 40, 140),
SCHED_TASK(run_nav_updates, 8, 100),
SCHED_TASK(update_thr_average, 4, 90),
SCHED_TASK(three_hz_loop, 133, 75),
SCHED_TASK(compass_accumulate, 4, 100),
SCHED_TASK(barometer_accumulate, 8, 90),
SCHED_TASK(update_batt_compass, 10, 120),
SCHED_TASK(read_aux_switches, 10, 50),
SCHED_TASK(arm_motors_check, 10, 50),
SCHED_TASK(auto_disarm_check, 10, 50),
SCHED_TASK(auto_trim, 10, 75),
SCHED_TASK(update_altitude, 10, 140),
SCHED_TASK(run_nav_updates, 50, 100),
SCHED_TASK(update_thr_average, 100, 90),
SCHED_TASK(three_hz_loop, 3, 75),
SCHED_TASK(compass_accumulate, 100, 100),
SCHED_TASK(barometer_accumulate, 50, 90),
#if PRECISION_LANDING == ENABLED
SCHED_TASK(update_precland, 8, 50),
SCHED_TASK(update_precland, 50, 50),
#endif
#if FRAME_CONFIG == HELI_FRAME
SCHED_TASK(check_dynamic_flight, 8, 75),
SCHED_TASK(check_dynamic_flight, 50, 75),
#endif
SCHED_TASK(update_notify, 8, 90),
SCHED_TASK(one_hz_loop, 400, 100),
SCHED_TASK(ekf_check, 40, 75),
SCHED_TASK(landinggear_update, 40, 75),
SCHED_TASK(lost_vehicle_check, 40, 50),
SCHED_TASK(gcs_check_input, 1, 180),
SCHED_TASK(gcs_send_heartbeat, 400, 110),
SCHED_TASK(gcs_send_deferred, 8, 550),
SCHED_TASK(gcs_data_stream_send, 8, 550),
SCHED_TASK(update_mount, 8, 75),
SCHED_TASK(ten_hz_logging_loop, 40, 350),
SCHED_TASK(fifty_hz_logging_loop, 8, 110),
SCHED_TASK(full_rate_logging_loop, 1, 100),
SCHED_TASK(dataflash_periodic, 1, 300),
SCHED_TASK(perf_update, 4000, 75),
SCHED_TASK(read_receiver_rssi, 40, 75),
SCHED_TASK(rpm_update, 40, 200),
SCHED_TASK(compass_cal_update, 4, 100),
SCHED_TASK(update_notify, 50, 90),
SCHED_TASK(one_hz_loop, 1, 100),
SCHED_TASK(ekf_check, 10, 75),
SCHED_TASK(landinggear_update, 10, 75),
SCHED_TASK(lost_vehicle_check, 10, 50),
SCHED_TASK(gcs_check_input, 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(update_mount, 50, 75),
SCHED_TASK(ten_hz_logging_loop, 10, 350),
SCHED_TASK(fifty_hz_logging_loop, 50, 110),
SCHED_TASK(full_rate_logging_loop,400, 100),
SCHED_TASK(dataflash_periodic, 400, 300),
SCHED_TASK(perf_update, 0.1, 75),
SCHED_TASK(read_receiver_rssi, 10, 75),
SCHED_TASK(rpm_update, 10, 200),
SCHED_TASK(compass_cal_update, 100, 100),
#if ADSB_ENABLED == ENABLED
SCHED_TASK(adsb_update, 400, 100),
SCHED_TASK(adsb_update, 1, 100),
#endif
#if FRSKY_TELEM_ENABLED == ENABLED
SCHED_TASK(frsky_telemetry_send, 80, 75),
SCHED_TASK(frsky_telemetry_send, 5, 75),
#endif
#if EPM_ENABLED == ENABLED
SCHED_TASK(epm_update, 40, 75),
SCHED_TASK(epm_update, 10, 75),
#endif
#ifdef USERHOOK_FASTLOOP
SCHED_TASK(userhook_FastLoop, 4, 75),
SCHED_TASK(userhook_FastLoop, 100, 75),
#endif
#ifdef USERHOOK_50HZLOOP
SCHED_TASK(userhook_50Hz, 8, 75),
SCHED_TASK(userhook_50Hz, 50, 75),
#endif
#ifdef USERHOOK_MEDIUMLOOP
SCHED_TASK(userhook_MediumLoop, 40, 75),
SCHED_TASK(userhook_MediumLoop, 10, 75),
#endif
#ifdef USERHOOK_SLOWLOOP
SCHED_TASK(userhook_SlowLoop, 120, 75),
SCHED_TASK(userhook_SlowLoop, 3.3, 75),
#endif
#ifdef USERHOOK_SUPERSLOWLOOP
SCHED_TASK(userhook_SuperSlowLoop, 400, 75),
SCHED_TASK(userhook_SuperSlowLoop, 1, 75),
#endif
};

View File

@ -22,7 +22,6 @@
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
Copter::Copter(void) :
ins_sample_rate(AP_InertialSensor::RATE_400HZ),
flight_modes(&g.flight_mode1),
sonar_enabled(true),
mission(ahrs,

View File

@ -166,9 +166,6 @@ private:
// Dataflash
DataFlash_Class DataFlash{FIRMWARE_STRING};
// the rate we run the main loop at
const AP_InertialSensor::Sample_rate ins_sample_rate;
AP_GPS gps;
// flight modes convenience array

View File

@ -298,7 +298,7 @@ void Copter::startup_INS_ground()
ahrs.set_vehicle_class(AHRS_VEHICLE_COPTER);
// Warm up and calibrate gyro offsets
ins.init(ins_sample_rate);
ins.init(scheduler.get_loop_rate_hz());
// reset ahrs including gyro bias
ahrs.reset();

View File

@ -84,7 +84,7 @@ int8_t Copter::test_compass(uint8_t argc, const Menu::arg *argv)
report_compass();
// we need the AHRS initialised for this test
ins.init(ins_sample_rate);
ins.init(scheduler.get_loop_rate_hz());
ahrs.reset();
int16_t counter = 0;
float heading = 0;
@ -152,7 +152,7 @@ int8_t Copter::test_ins(uint8_t argc, const Menu::arg *argv)
delay(1000);
ahrs.init();
ins.init(ins_sample_rate);
ins.init(scheduler.get_loop_rate_hz());
cliSerial->printf("...done\n");
delay(50);