Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Move update calls for Notify up to AP_Vehicle #13672

Merged
merged 6 commits into from
May 17, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion AntennaTracker/Tracker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
};
Expand Down
1 change: 0 additions & 1 deletion ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down
1 change: 0 additions & 1 deletion ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down
1 change: 0 additions & 1 deletion ArduSub/ArduSub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down
1 change: 0 additions & 1 deletion Rover/Rover.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Vehicle/AP_Vehicle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down