Plane: remove annoying ice_update shim
This commit is contained in:
parent
e404562544
commit
85f339caae
@ -57,7 +57,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
||||
SCHED_TASK_CLASS(AP_Baro, &plane.barometer, accumulate, 50, 150),
|
||||
SCHED_TASK(update_notify, 50, 300),
|
||||
SCHED_TASK(read_rangefinder, 50, 100),
|
||||
SCHED_TASK(ice_update, 10, 100),
|
||||
SCHED_TASK_CLASS(AP_ICEngine, &plane.g2.ice_control, update, 10, 100),
|
||||
SCHED_TASK(compass_cal_update, 50, 50),
|
||||
SCHED_TASK(accel_cal_update, 10, 50),
|
||||
#if OPTFLOW == ENABLED
|
||||
|
@ -915,7 +915,6 @@ private:
|
||||
void read_rangefinder(void);
|
||||
void read_airspeed(void);
|
||||
void rpm_update(void);
|
||||
void ice_update(void);
|
||||
void init_ardupilot();
|
||||
void startup_ground(void);
|
||||
enum FlightMode get_previous_mode();
|
||||
|
@ -104,13 +104,6 @@ void Plane::rpm_update(void)
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
update AP_ICEngine
|
||||
*/
|
||||
void Plane::ice_update(void)
|
||||
{
|
||||
g2.ice_control.update();
|
||||
}
|
||||
// update error mask of sensors and subsystems. The mask
|
||||
// uses the MAV_SYS_STATUS_* values from mavlink. If a bit is set
|
||||
// then it indicates that the sensor or subsystem is present but
|
||||
|
Loading…
Reference in New Issue
Block a user