diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index ca4f0f7905..94828ac47c 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -16,6 +16,8 @@ param set-default COM_POS_FS_EPV 30 param set-default COM_POS_FS_GAIN 0 param set-default COM_POS_FS_PROB 1 param set-default COM_VEL_FS_EVH 5 +# Disable preflight disarm to not interfere with external launching +param set-default COM_DISARM_PRFLT -1 param set-default EKF2_ARSP_THR 8 param set-default EKF2_FUSE_BETA 1 diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 31fcc4756f..35689eaff9 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -287,21 +287,19 @@ PARAM_DEFINE_INT32(COM_RC_ARM_HYST, 1000); PARAM_DEFINE_FLOAT(COM_DISARM_LAND, 2.0f); /** - * Time-out for auto disarm if too slow to takeoff + * Time-out for auto disarm if not taking off * - * A non-zero, positive value specifies the time after arming, in seconds, within which the - * vehicle must take off (after which it will automatically disarm). + * A non-zero, positive value specifies the time in seconds, within which the + * vehicle is expected to take off after arming. In case the vehicle didn't takeoff + * within the timout it disamrs again. * - * This is set to 25 seconds to ensure a system will not disarm if the pilot is not immediately - * taking off, but not so long that a system is completely forgotten about. - * - * A zero or negative value means that automatic disarming triggered by a pre-takeoff timeout is disabled. + * A negative value disables autmoatic disarming triggered by a pre-takeoff timeout. * * @group Commander * @unit s * @decimal 2 */ -PARAM_DEFINE_FLOAT(COM_DISARM_PRFLT, 25.0f); +PARAM_DEFINE_FLOAT(COM_DISARM_PRFLT, 10.0f); /**