|
|
|
@ -36,21 +36,23 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
@@ -36,21 +36,23 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
|
|
|
|
SCHED_TASK(three_hz_loop, 3, 75), |
|
|
|
|
SCHED_TASK(update_turn_counter, 10, 50), |
|
|
|
|
SCHED_TASK(compass_accumulate, 100, 100), |
|
|
|
|
SCHED_TASK(barometer_accumulate, 50, 90), |
|
|
|
|
SCHED_TASK(update_notify, 50, 90), |
|
|
|
|
SCHED_TASK_CLASS(AP_Baro, &sub.barometer, accumulate, 50, 90), |
|
|
|
|
SCHED_TASK_CLASS(AP_Notify, &sub.notify, update, 50, 90), |
|
|
|
|
SCHED_TASK(one_hz_loop, 1, 100), |
|
|
|
|
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), |
|
|
|
|
#if MOUNT == ENABLED |
|
|
|
|
SCHED_TASK_CLASS(AP_Mount, &sub.camera_mount, update, 50, 75), |
|
|
|
|
#endif |
|
|
|
|
#if CAMERA == ENABLED |
|
|
|
|
SCHED_TASK(update_trigger, 50, 75), |
|
|
|
|
SCHED_TASK_CLASS(AP_Camera, &sub.camera, update_trigger, 50, 75), |
|
|
|
|
#endif |
|
|
|
|
SCHED_TASK(ten_hz_logging_loop, 10, 350), |
|
|
|
|
SCHED_TASK(twentyfive_hz_logging, 25, 110), |
|
|
|
|
SCHED_TASK(dataflash_periodic, 400, 300), |
|
|
|
|
SCHED_TASK(ins_periodic, 400, 50), |
|
|
|
|
SCHED_TASK_CLASS(DataFlash_Class, &sub.DataFlash, periodic_tasks, 400, 300), |
|
|
|
|
SCHED_TASK_CLASS(AP_InertialSensor, &sub.ins, periodic, 400, 50), |
|
|
|
|
SCHED_TASK(perf_update, 0.1, 75), |
|
|
|
|
#if RPM_ENABLED == ENABLED |
|
|
|
|
SCHED_TASK(rpm_update, 10, 200), |
|
|
|
@ -59,7 +61,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
@@ -59,7 +61,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
|
|
|
|
SCHED_TASK(accel_cal_update, 10, 100), |
|
|
|
|
SCHED_TASK(terrain_update, 10, 100), |
|
|
|
|
#if GRIPPER_ENABLED == ENABLED |
|
|
|
|
SCHED_TASK(gripper_update, 10, 75), |
|
|
|
|
SCHED_TASK_CLASS(AP_Gripper, &g2.gripper, update, 10, 75), |
|
|
|
|
#endif |
|
|
|
|
#ifdef USERHOOK_FASTLOOP |
|
|
|
|
SCHED_TASK(userhook_FastLoop, 100, 75), |
|
|
|
@ -209,31 +211,6 @@ void Sub::fifty_hz_loop()
@@ -209,31 +211,6 @@ void Sub::fifty_hz_loop()
|
|
|
|
|
SRV_Channels::output_ch_all(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// updates the status of notify
|
|
|
|
|
// should be called at 50hz
|
|
|
|
|
void Sub::update_notify() |
|
|
|
|
{ |
|
|
|
|
notify.update(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// update_mount - update camera mount position
|
|
|
|
|
// should be run at 50hz
|
|
|
|
|
void Sub::update_mount() |
|
|
|
|
{ |
|
|
|
|
#if MOUNT == ENABLED |
|
|
|
|
// update camera mount's position
|
|
|
|
|
camera_mount.update(); |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#if CAMERA == ENABLED |
|
|
|
|
// update camera trigger
|
|
|
|
|
void Sub::update_trigger(void) |
|
|
|
|
{ |
|
|
|
|
camera.update_trigger(); |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// update_batt_compass - read battery and compass
|
|
|
|
|
// should be called at 10hz
|
|
|
|
|
void Sub::update_batt_compass(void) |
|
|
|
@ -308,16 +285,6 @@ void Sub::twentyfive_hz_logging()
@@ -308,16 +285,6 @@ void Sub::twentyfive_hz_logging()
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Sub::dataflash_periodic(void) |
|
|
|
|
{ |
|
|
|
|
DataFlash.periodic_tasks(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void Sub::ins_periodic() |
|
|
|
|
{ |
|
|
|
|
ins.periodic(); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// three_hz_loop - 3.3hz loop
|
|
|
|
|
void Sub::three_hz_loop() |
|
|
|
|
{ |
|
|
|
|