forked from Archive/PX4-Autopilot
commander: make auto disarm timeout float
such that fractions of a second are configurable
This commit is contained in:
parent
658b957888
commit
0c6bffb66a
|
@ -108,7 +108,7 @@ then
|
|||
param set SENS_DPRES_OFF 0.001
|
||||
param set CBRK_AIRSPD_CHK 0
|
||||
|
||||
param set COM_DISARM_LAND 3
|
||||
param set COM_DISARM_LAND 0.1
|
||||
param set COM_OBL_ACT 2
|
||||
param set COM_OBL_RC_ACT 0
|
||||
param set COM_OF_LOSS_T 5
|
||||
|
|
|
@ -14,7 +14,7 @@ if [ $AUTOCNF == yes ]
|
|||
then
|
||||
param set BAT_N_CELLS 3
|
||||
|
||||
param set COM_DISARM_LAND 5
|
||||
param set COM_DISARM_LAND 5.0
|
||||
param set COM_RC_IN_MODE 1
|
||||
|
||||
param set EKF2_AID_MASK 1
|
||||
|
|
|
@ -25,7 +25,7 @@ then
|
|||
param set BAT_N_CELLS 4
|
||||
param set BAT_R_INTERNAL 0.0025
|
||||
|
||||
param set COM_DISARM_LAND 5
|
||||
param set COM_DISARM_LAND 5.0
|
||||
|
||||
param set VT_TYPE 2
|
||||
param set VT_MOT_COUNT 4
|
||||
|
|
|
@ -32,7 +32,7 @@ then
|
|||
|
||||
# takeoff, land and RTL settings
|
||||
param set MIS_TAKEOFF_ALT 4.0
|
||||
param set COM_DISARM_LAND 1
|
||||
param set COM_DISARM_LAND 1.0
|
||||
param set RTL_LAND_DELAY 1
|
||||
param set RTL_DESCEND_ALT 5.0
|
||||
param set RTL_RETURN_ALT 15.0
|
||||
|
|
|
@ -23,7 +23,7 @@ if [ $AUTOCNF == yes ]
|
|||
then
|
||||
# Set all params here, then disable autoconfig
|
||||
|
||||
param set COM_DISARM_LAND 3
|
||||
param set COM_DISARM_LAND 3.0
|
||||
|
||||
param set LNDMC_Z_VEL_MAX 2.0000
|
||||
|
||||
|
|
|
@ -1383,7 +1383,7 @@ Commander::run()
|
|||
float ef_time_thres = 1000.0f;
|
||||
uint64_t timestamp_engine_healthy = 0; /**< absolute time when engine was healty */
|
||||
|
||||
int32_t disarm_when_landed = 0;
|
||||
float disarm_when_landed_timeout = 0.f;
|
||||
|
||||
/* check which state machines for changes, clear "changed" flag */
|
||||
bool main_state_changed = false;
|
||||
|
@ -1481,7 +1481,7 @@ Commander::run()
|
|||
param_get(_param_ef_current2throttle_thres, &ef_current2throttle_thres);
|
||||
param_get(_param_ef_time_thres, &ef_time_thres);
|
||||
param_get(_param_geofence_action, &geofence_action);
|
||||
param_get(_param_disarm_land, &disarm_when_landed);
|
||||
param_get(_param_disarm_land, &disarm_when_landed_timeout);
|
||||
param_get(_param_flight_uuid, &flight_uuid);
|
||||
|
||||
// If we update parameters the first time
|
||||
|
@ -1489,7 +1489,7 @@ Commander::run()
|
|||
// After that it will be set in the main state
|
||||
// machine based on the arming state.
|
||||
if (param_init_forced) {
|
||||
auto_disarm_hysteresis.set_hysteresis_time_from(false, disarm_when_landed * 1_s);
|
||||
auto_disarm_hysteresis.set_hysteresis_time_from(false, disarm_when_landed_timeout * 1_s);
|
||||
}
|
||||
|
||||
param_get(_param_offboard_loss_timeout, &offboard_loss_timeout);
|
||||
|
@ -1719,17 +1719,16 @@ Commander::run()
|
|||
was_falling = land_detector.freefall;
|
||||
}
|
||||
|
||||
/* Update hysteresis time. Use a time of factor 5 longer if we have not taken off yet. */
|
||||
hrt_abstime timeout_time = disarm_when_landed * 1_s;
|
||||
|
||||
// Auto disarm when landed
|
||||
if (!have_taken_off_since_arming) {
|
||||
timeout_time *= 5;
|
||||
// pilot has ten seconds time to take off
|
||||
auto_disarm_hysteresis.set_hysteresis_time_from(false, 10_s);
|
||||
} else {
|
||||
auto_disarm_hysteresis.set_hysteresis_time_from(false, disarm_when_landed_timeout * 1_s);
|
||||
}
|
||||
|
||||
auto_disarm_hysteresis.set_hysteresis_time_from(false, timeout_time);
|
||||
|
||||
// Check for auto-disarm
|
||||
if (armed.armed && land_detector.landed && disarm_when_landed > 0) {
|
||||
if (armed.armed && land_detector.landed && disarm_when_landed_timeout > FLT_EPSILON) {
|
||||
auto_disarm_hysteresis.set_state_and_update(true);
|
||||
|
||||
} else {
|
||||
|
|
|
@ -278,18 +278,17 @@ PARAM_DEFINE_INT32(COM_RC_ARM_HYST, 1000);
|
|||
* automatically disarmed in case a landing situation has been detected during this period.
|
||||
*
|
||||
* The vehicle will also auto-disarm right after arming if it has not even flown, however the time
|
||||
* will be longer by a factor of 5.
|
||||
* will always be 10 seconds such that the pilot has enough time to take off.
|
||||
*
|
||||
* A value of zero means that automatic disarming is disabled.
|
||||
* A negative value means that automatic disarming triggered by landing detection is disabled.
|
||||
*
|
||||
* @group Commander
|
||||
* @min 0
|
||||
* @min -1
|
||||
* @max 20
|
||||
* @unit s
|
||||
* @decimal 0
|
||||
* @increment 1
|
||||
* @decimal 2
|
||||
*/
|
||||
PARAM_DEFINE_INT32(COM_DISARM_LAND, 0);
|
||||
PARAM_DEFINE_FLOAT(COM_DISARM_LAND, -1.0f);
|
||||
|
||||
/**
|
||||
* Allow arming without GPS
|
||||
|
|
Loading…
Reference in New Issue