mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Copter: added DISARM_DELAY parameter
this allows automatic disarming to be disabled, or set to a shorter or longer time as appropriate for the user Originally committed by Tridge, merged to AC3.3 with conflict.
This commit is contained in:
parent
c0ea1f70ef
commit
6e93f111c9
@ -447,6 +447,14 @@ const AP_Param::Info Copter::var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
GSCALAR(arming_check, "ARMING_CHECK", ARMING_CHECK_ALL),
|
||||
|
||||
// @Param: DISARM_DELAY
|
||||
// @DisplayName: Disarm delay
|
||||
// @Description: Delay before automatic disarm in seconds. A value of zero disables auto disarm.
|
||||
// @Units: Seconds
|
||||
// @Range: 0 127
|
||||
// @User: Advanced
|
||||
GSCALAR(disarm_delay, "DISARM_DELAY", AUTO_DISARMING_DELAY),
|
||||
|
||||
// @Param: ANGLE_MAX
|
||||
// @DisplayName: Angle Max
|
||||
// @Description: Maximum lean angle in all flight modes
|
||||
|
@ -170,6 +170,7 @@ public:
|
||||
// 90: Motors
|
||||
//
|
||||
k_param_motors = 90,
|
||||
k_param_disarm_delay,
|
||||
|
||||
//
|
||||
// 100: Inertial Nav
|
||||
@ -427,6 +428,7 @@ public:
|
||||
AP_Int8 ch11_option;
|
||||
AP_Int8 ch12_option;
|
||||
AP_Int8 arming_check;
|
||||
AP_Int8 disarm_delay;
|
||||
|
||||
AP_Int8 land_repositioning;
|
||||
AP_Int8 fs_ekf_action;
|
||||
|
@ -688,6 +688,10 @@
|
||||
# define ALT_HOLD_ACCEL_MAX 250 // if you change this you must also update the duplicate declaration in AC_WPNav.h
|
||||
#endif
|
||||
|
||||
#ifndef AUTO_DISARMING_DELAY
|
||||
# define AUTO_DISARMING_DELAY 10
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Dataflash logging control
|
||||
//
|
||||
|
@ -5,8 +5,6 @@
|
||||
#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_LONG 10 // called at 1hz so 10 seconds
|
||||
#define AUTO_DISARMING_DELAY_SHORT 5 // called at 1hz so 5 seconds
|
||||
#define LOST_VEHICLE_DELAY 10 // called at 10hz so 1 second
|
||||
|
||||
static uint8_t auto_disarming_counter;
|
||||
@ -75,10 +73,11 @@ void Copter::arm_motors_check()
|
||||
// called at 1hz
|
||||
void Copter::auto_disarm_check()
|
||||
{
|
||||
uint8_t disarm_delay = AUTO_DISARMING_DELAY_LONG;
|
||||
uint8_t disarm_delay = constrain_int16(g.disarm_delay, 0, 127);
|
||||
|
||||
// exit immediately if we are already disarmed
|
||||
if (!motors.armed()) {
|
||||
// exit immediately if we are already disarmed, or if auto
|
||||
// disarming is disabled
|
||||
if (!motors.armed() || disarm_delay == 0) {
|
||||
auto_disarming_counter = 0;
|
||||
return;
|
||||
}
|
||||
@ -86,14 +85,9 @@ void Copter::auto_disarm_check()
|
||||
// always allow auto disarm if using interlock switch or motors are Emergency Stopped
|
||||
if ((ap.using_interlock && !motors.get_interlock()) || ap.motor_emergency_stop) {
|
||||
auto_disarming_counter++;
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// helicopters do not use short disarm delay as they could be in auto-rotation.
|
||||
disarm_delay = AUTO_DISARMING_DELAY_LONG;
|
||||
#else
|
||||
// use a shorter delay if using throttle interlock switch or Emergency Stop, because it is less
|
||||
// obvious the copter is armed as the motors will not be spinning
|
||||
disarm_delay = AUTO_DISARMING_DELAY_SHORT;
|
||||
#endif
|
||||
disarm_delay /= 2;
|
||||
} else {
|
||||
bool sprung_throttle_stick = (g.throttle_behavior & THR_BEHAVE_FEEDBACK_FROM_MID_STICK) != 0;
|
||||
bool thr_low;
|
||||
|
Loading…
Reference in New Issue
Block a user