Sub: Remove unused lost_vehicle_check

This commit is contained in:
Jacob Walser 2017-03-24 15:10:16 -04:00
parent 1a68fce2d0
commit bc5d9b1a19
3 changed files with 0 additions and 27 deletions

View File

@ -41,7 +41,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
SCHED_TASK(update_notify, 50, 90),
SCHED_TASK(one_hz_loop, 1, 100),
SCHED_TASK(ekf_check, 10, 75),
SCHED_TASK(lost_vehicle_check, 10, 50),
SCHED_TASK(gcs_check_input, 400, 180),
SCHED_TASK(gcs_send_heartbeat, 1, 110),
SCHED_TASK(gcs_send_deferred, 50, 550),

View File

@ -659,7 +659,6 @@ private:
bool init_arm_motors(bool arming_from_gcs);
void init_disarm_motors();
void motors_output();
void lost_vehicle_check();
void run_nav_updates(void);
void calc_position();
void calc_distance_and_bearing();

View File

@ -1,7 +1,5 @@
#include "Sub.h"
#define LOST_VEHICLE_DELAY 10 // called at 10hz so 1 second
// init_arm_motors - performs arming process including initialisation of barometer and gyros
// returns false if arming failed because of pre-arm checks, arming checks or a gyro calibration failure
bool Sub::init_arm_motors(bool arming_from_gcs)
@ -137,29 +135,6 @@ void Sub::motors_output()
}
}
// check for pilot stick input to trigger lost vehicle alarm
void Sub::lost_vehicle_check()
{
static uint8_t soundalarm_counter;
// ensure throttle is down, motors not armed, pitch and roll rc at max. Note: rc1=roll rc2=pitch
if (ap.throttle_zero && !motors.armed() && (channel_roll->get_control_in() > 4000) && (channel_pitch->get_control_in() > 4000)) {
if (soundalarm_counter >= LOST_VEHICLE_DELAY) {
if (AP_Notify::flags.vehicle_lost == false) {
AP_Notify::flags.vehicle_lost = true;
gcs_send_text(MAV_SEVERITY_NOTICE,"Locate vehicle alarm");
}
} else {
soundalarm_counter++;
}
} else {
soundalarm_counter = 0;
if (AP_Notify::flags.vehicle_lost == true) {
AP_Notify::flags.vehicle_lost = false;
}
}
}
// translate wpnav roll/pitch outputs to lateral/forward
void Sub::translate_wpnav_rp(float &lateral_out, float &forward_out)
{