mirror of https://github.com/ArduPilot/ardupilot
Sub: Remove old RC-style arm and disarm checks
This commit is contained in:
parent
dd2d0711c0
commit
e2f75d2451
|
@ -91,7 +91,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
||||||
#endif
|
#endif
|
||||||
SCHED_TASK(update_batt_compass, 10, 120),
|
SCHED_TASK(update_batt_compass, 10, 120),
|
||||||
SCHED_TASK(read_aux_switches, 10, 50),
|
SCHED_TASK(read_aux_switches, 10, 50),
|
||||||
SCHED_TASK(arm_motors_check, 10, 50),
|
|
||||||
SCHED_TASK(auto_disarm_check, 10, 50),
|
SCHED_TASK(auto_disarm_check, 10, 50),
|
||||||
SCHED_TASK(auto_trim, 10, 75),
|
SCHED_TASK(auto_trim, 10, 75),
|
||||||
SCHED_TASK(read_rangefinder, 20, 100),
|
SCHED_TASK(read_rangefinder, 20, 100),
|
||||||
|
|
|
@ -852,7 +852,6 @@ private:
|
||||||
bool mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc);
|
bool mavlink_motor_test_check(mavlink_channel_t chan, bool check_rc);
|
||||||
uint8_t mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value, float timeout_sec);
|
uint8_t mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, uint16_t throttle_value, float timeout_sec);
|
||||||
void motor_test_stop();
|
void motor_test_stop();
|
||||||
void arm_motors_check();
|
|
||||||
void auto_disarm_check();
|
void auto_disarm_check();
|
||||||
bool init_arm_motors(bool arming_from_gcs);
|
bool init_arm_motors(bool arming_from_gcs);
|
||||||
void update_arming_checks(void);
|
void update_arming_checks(void);
|
||||||
|
|
Loading…
Reference in New Issue