mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: remove pointless wrappers around RC_Channels functions
This commit is contained in:
parent
d49431488e
commit
d4e88bc6ba
@ -90,7 +90,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
||||
#endif
|
||||
SCHED_TASK_CLASS(AP_InertialSensor, &plane.ins, periodic, 50, 50),
|
||||
SCHED_TASK(avoidance_adsb_update, 10, 100),
|
||||
SCHED_TASK(read_aux_all, 10, 200),
|
||||
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&plane.g2.rc_channels, read_aux_all, 10, 200),
|
||||
SCHED_TASK_CLASS(AP_Button, &plane.g2.button, update, 5, 100),
|
||||
#if STATS_ENABLED == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Stats, &plane.g2.stats, update, 1, 100),
|
||||
@ -134,11 +134,6 @@ void Plane::update_soft_armed()
|
||||
DataFlash.set_vehicle_armed(hal.util->get_soft_armed());
|
||||
}
|
||||
|
||||
void Plane::read_aux_all()
|
||||
{
|
||||
plane.g2.rc_channels.read_aux_all();
|
||||
}
|
||||
|
||||
// update AHRS system
|
||||
void Plane::ahrs_update()
|
||||
{
|
||||
|
@ -1060,8 +1060,6 @@ private:
|
||||
void update_soaring();
|
||||
#endif
|
||||
|
||||
void read_aux_all();
|
||||
|
||||
bool reversed_throttle;
|
||||
bool have_reverse_throttle_rc_option;
|
||||
bool allow_reverse_thrust(void) const;
|
||||
|
Loading…
Reference in New Issue
Block a user