mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: remove pointless wrappers around RC_Channels functions
This commit is contained in:
parent
c9714ae962
commit
d49431488e
@ -90,7 +90,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
|||||||
SCHED_TASK_CLASS(OpticalFlow, &copter.optflow, update, 200, 160),
|
SCHED_TASK_CLASS(OpticalFlow, &copter.optflow, update, 200, 160),
|
||||||
#endif
|
#endif
|
||||||
SCHED_TASK(update_batt_compass, 10, 120),
|
SCHED_TASK(update_batt_compass, 10, 120),
|
||||||
SCHED_TASK(read_aux_all, 10, 50),
|
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&copter.g2.rc_channels, read_aux_all, 10, 50),
|
||||||
SCHED_TASK(arm_motors_check, 10, 50),
|
SCHED_TASK(arm_motors_check, 10, 50),
|
||||||
#if TOY_MODE_ENABLED == ENABLED
|
#if TOY_MODE_ENABLED == ENABLED
|
||||||
SCHED_TASK_CLASS(ToyMode, &copter.g2.toy_mode, update, 10, 50),
|
SCHED_TASK_CLASS(ToyMode, &copter.g2.toy_mode, update, 10, 50),
|
||||||
@ -198,12 +198,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
|||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
void Copter::read_aux_all()
|
|
||||||
{
|
|
||||||
copter.g2.rc_channels.read_aux_all();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
constexpr int8_t Copter::_failsafe_priorities[7];
|
constexpr int8_t Copter::_failsafe_priorities[7];
|
||||||
|
|
||||||
void Copter::setup()
|
void Copter::setup()
|
||||||
|
@ -633,7 +633,6 @@ private:
|
|||||||
void rc_loop();
|
void rc_loop();
|
||||||
void throttle_loop();
|
void throttle_loop();
|
||||||
void update_batt_compass(void);
|
void update_batt_compass(void);
|
||||||
void read_aux_all(void);
|
|
||||||
void fourhundred_hz_logging();
|
void fourhundred_hz_logging();
|
||||||
void ten_hz_logging_loop();
|
void ten_hz_logging_loop();
|
||||||
void twentyfive_hz_logging();
|
void twentyfive_hz_logging();
|
||||||
|
@ -27,11 +27,6 @@ class RC_Channels_Copter : public RC_Channels
|
|||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
|
||||||
// this must be implemented for the AP_Scheduler functor to work:
|
|
||||||
void read_aux_all() override {
|
|
||||||
RC_Channels::read_aux_all();
|
|
||||||
}
|
|
||||||
|
|
||||||
bool has_valid_input() const override;
|
bool has_valid_input() const override;
|
||||||
|
|
||||||
RC_Channel_Copter obj_channels[NUM_RC_CHANNELS];
|
RC_Channel_Copter obj_channels[NUM_RC_CHANNELS];
|
||||||
|
Loading…
Reference in New Issue
Block a user