mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: remove pointless update_notify shim
This commit is contained in:
parent
006583d812
commit
3a4cbdd41f
@ -56,7 +56,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
||||
SCHED_TASK_CLASS(AP_ServoRelayEvents, &plane.ServoRelayEvents, update_events, 50, 150),
|
||||
SCHED_TASK_CLASS(AP_BattMonitor, &plane.battery, read, 10, 300),
|
||||
SCHED_TASK_CLASS(AP_Baro, &plane.barometer, accumulate, 50, 150),
|
||||
SCHED_TASK(update_notify, 50, 300),
|
||||
SCHED_TASK_CLASS(AP_Notify, &plane.notify, update, 50, 300),
|
||||
SCHED_TASK(read_rangefinder, 50, 100),
|
||||
SCHED_TASK_CLASS(AP_ICEngine, &plane.g2.ice_control, update, 10, 100),
|
||||
SCHED_TASK(compass_cal_update, 50, 50),
|
||||
|
@ -945,7 +945,6 @@ private:
|
||||
void check_long_failsafe();
|
||||
void check_short_failsafe();
|
||||
void startup_INS_ground(void);
|
||||
void update_notify();
|
||||
bool should_log(uint32_t mask);
|
||||
int8_t throttle_percentage(void);
|
||||
void change_arm_state(void);
|
||||
|
@ -419,13 +419,6 @@ void Plane::startup_INS_ground(void)
|
||||
}
|
||||
}
|
||||
|
||||
// updates the status of the notify objects
|
||||
// should be called at 50hz
|
||||
void Plane::update_notify()
|
||||
{
|
||||
notify.update();
|
||||
}
|
||||
|
||||
// sets notify object flight mode information
|
||||
void Plane::notify_mode(const Mode& mode)
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user