From 7cbc7d8161fec2c8f3fb18b8e691c54b9a4fe3e6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 25 Feb 2020 14:19:27 +1100 Subject: [PATCH 1/6] AP_Vehicle: move call of notify.update up to AP_Vehicle --- libraries/AP_Vehicle/AP_Vehicle.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index f5536d1ab871d..b88427fcf99e7 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -392,6 +392,7 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = { #if COMPASS_CAL_ENABLED SCHED_TASK_CLASS(Compass, &vehicle.compass, cal_update, 100, 200, 75), #endif + SCHED_TASK_CLASS(AP_Notify, &vehicle.notify, update, 50, 300, 78), #if HAL_NMEA_OUTPUT_ENABLED SCHED_TASK_CLASS(AP_NMEA_Output, &vehicle.nmea, update, 50, 50, 180), #endif From e78273c195b7c82a81aef35318f003901e64e339 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 25 Feb 2020 14:19:27 +1100 Subject: [PATCH 2/6] AntennaTracker: move call of notify.update up to AP_Vehicle --- AntennaTracker/Tracker.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/AntennaTracker/Tracker.cpp b/AntennaTracker/Tracker.cpp index e7e1a384587e7..f3284e985ec35 100644 --- a/AntennaTracker/Tracker.cpp +++ b/AntennaTracker/Tracker.cpp @@ -64,7 +64,6 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Logger, &tracker.logger, periodic_tasks, 50, 300, 65), #endif SCHED_TASK_CLASS(AP_InertialSensor, &tracker.ins, periodic, 50, 50, 70), - SCHED_TASK_CLASS(AP_Notify, &tracker.notify, update, 50, 100, 75), SCHED_TASK(one_second_loop, 1, 3900, 80), SCHED_TASK(stats_update, 1, 200, 90), }; From 8f1d14ae362e1b781f356093ccf0dc7312dc9237 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 25 Feb 2020 14:19:27 +1100 Subject: [PATCH 3/6] APMrover2: move call of notify.update up to AP_Vehicle --- Rover/Rover.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index 2ef70f1c9e986..9e5ba4f93dc28 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -116,7 +116,6 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { SCHED_TASK(fence_check, 10, 200, 84), SCHED_TASK(ekf_check, 10, 100, 87), SCHED_TASK_CLASS(ModeSmartRTL, &rover.mode_smartrtl, save_position, 3, 200, 90), - SCHED_TASK_CLASS(AP_Notify, &rover.notify, update, 50, 300, 93), SCHED_TASK(one_second_loop, 1, 1500, 96), #if HAL_SPRAYER_ENABLED SCHED_TASK_CLASS(AC_Sprayer, &rover.g2.sprayer, update, 3, 90, 99), From d9b808545a4384a4a58b20fca5b8d3205ddc4deb Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 25 Feb 2020 14:19:27 +1100 Subject: [PATCH 4/6] ArduCopter: move call of notify.update up to AP_Vehicle --- ArduCopter/Copter.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 4c24723e8d1f5..170ed3d649e2e 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -189,7 +189,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if LOGGING_ENABLED == ENABLED SCHED_TASK(loop_rate_logging, LOOP_RATE, 50, 75), #endif - SCHED_TASK_CLASS(AP_Notify, &copter.notify, update, 50, 90, 78), SCHED_TASK(one_hz_loop, 1, 100, 81), SCHED_TASK(ekf_check, 10, 75, 84), SCHED_TASK(check_vibration, 10, 50, 87), From a6d5c471ca79ed8461e3c9c4bcecf6e3fab9d98e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 25 Feb 2020 14:19:27 +1100 Subject: [PATCH 5/6] ArduPlane: move call of notify.update up to AP_Vehicle --- ArduPlane/ArduPlane.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 4a70c50c22220..2c68fa97ed8cf 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -80,7 +80,6 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_ServoRelayEvents, &plane.ServoRelayEvents, update_events, 50, 150, 63), SCHED_TASK_CLASS(AP_BattMonitor, &plane.battery, read, 10, 300, 66), SCHED_TASK_CLASS(AP_Baro, &plane.barometer, accumulate, 50, 150, 69), - SCHED_TASK_CLASS(AP_Notify, &plane.notify, update, 50, 300, 72), SCHED_TASK(read_rangefinder, 50, 100, 78), #if AP_ICENGINE_ENABLED SCHED_TASK_CLASS(AP_ICEngine, &plane.g2.ice_control, update, 10, 100, 81), From 6722c7054c2590774c1593efef18207a5f4baacb Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 25 Feb 2020 14:19:28 +1100 Subject: [PATCH 6/6] ArduSub: move call of notify.update up to AP_Vehicle --- ArduSub/ArduSub.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 918a189eb3413..4ccc431fa3218 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -80,7 +80,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { SCHED_TASK(three_hz_loop, 3, 75, 21), SCHED_TASK(update_turn_counter, 10, 50, 24), SCHED_TASK_CLASS(AP_Baro, &sub.barometer, accumulate, 50, 90, 27), - SCHED_TASK_CLASS(AP_Notify, &sub.notify, update, 50, 90, 30), SCHED_TASK(one_hz_loop, 1, 100, 33), SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_receive, 400, 180, 36), SCHED_TASK_CLASS(GCS, (GCS*)&sub._gcs, update_send, 400, 550, 39),