Copter: move auto disarm into a separate function

This commit is contained in:
Randy Mackay 2013-05-20 14:05:50 +09:00
parent 1dbe98b566
commit 6efdabb104
2 changed files with 25 additions and 21 deletions

View File

@ -766,8 +766,6 @@ static float dTnav;
static int16_t superslow_loopCounter;
// Loiter timer - Records how long we have been in loiter
static uint32_t rtl_loiter_start_time;
// disarms the copter while in Acro or Stabilize mode after 30 seconds of no flight
static uint8_t auto_disarming_counter;
// prevents duplicate GPS messages from entering system
static uint32_t last_gps_time;
// the time when the last HEARTBEAT message arrived from a GCS - used for triggering gcs failsafe
@ -1266,7 +1264,6 @@ static void slow_loop()
}
}
#define AUTO_DISARMING_DELAY 25
// super_slow_loop - runs at 1Hz
static void super_slow_loop()
{
@ -1281,19 +1278,8 @@ static void super_slow_loop()
// perform pre-arm checks
pre_arm_checks(false);
// this function disarms the copter if it has been sitting on the ground for any moment of time greater than 25 seconds
// but only of the control mode is manual
if((control_mode <= ACRO) && (g.rc_3.control_in == 0) && motors.armed()) {
auto_disarming_counter++;
if(auto_disarming_counter == AUTO_DISARMING_DELAY) {
init_disarm_motors();
}else if (auto_disarming_counter > AUTO_DISARMING_DELAY) {
auto_disarming_counter = AUTO_DISARMING_DELAY + 1;
}
}else{
auto_disarming_counter = 0;
}
// auto disarm checks
auto_disarm_check();
// agmatthews - USERHOOKS
#ifdef USERHOOK_SUPERSLOWLOOP

View File

@ -1,10 +1,9 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// 10 = 1 second
#define ARM_DELAY 20
#define DISARM_DELAY 20
#define AUTO_TRIM_DELAY 100
#define ARM_DELAY 20 // called at 10hz so 2 seconds
#define DISARM_DELAY 20 // called at 10hz so 2 seconds
#define AUTO_TRIM_DELAY 100 // called at 10hz so 10 seconds
#define AUTO_DISARMING_DELAY 25 // called at 1hz so 25 seconds
// arm_motors_check - checks for pilot input to arm or disarm the copter
// called at 10hz
@ -81,7 +80,26 @@ static void arm_motors_check()
}
}
// auto_disarm_check - disarms the copter if it has been sitting on the ground in manual mode with throttle low for at least 25 seconds
// called at 1hz
static void auto_disarm_check()
{
static uint8_t auto_disarming_counter;
if((control_mode <= ACRO) && (g.rc_3.control_in == 0) && motors.armed()) {
auto_disarming_counter++;
if(auto_disarming_counter == AUTO_DISARMING_DELAY) {
init_disarm_motors();
}else if (auto_disarming_counter > AUTO_DISARMING_DELAY) {
auto_disarming_counter = AUTO_DISARMING_DELAY + 1;
}
}else{
auto_disarming_counter = 0;
}
}
// init_arm_motors - performs arming process including initialisation of barometer and gyros
static void init_arm_motors()
{
// arming marker