Parameterize timeout for radio status

This commit is contained in:
Nico van Duijn 2020-02-05 17:11:02 +01:00 committed by Daniel Agar
parent c78572b471
commit 55372d7cbe
3 changed files with 22 additions and 4 deletions

View File

@ -1528,12 +1528,15 @@ Mavlink::update_rate_mult()
} else if (_radio_status_available) {
// check for RADIO_STATUS timeout and reset
if (hrt_elapsed_time(&_rstatus.timestamp) > 5_s) {
if (hrt_elapsed_time(&_rstatus.timestamp) > (_param_mav_radio_timeout.get() *
1_s)) {
PX4_ERR("instance %d: RADIO_STATUS timeout", _instance_id);
_radio_status_available = false;
_radio_status_critical = false;
_radio_status_mult = 1.0f;
if (_use_software_mav_throttling) {
_radio_status_critical = false;
_radio_status_mult = 1.0f;
}
}
hardware_mult *= _radio_status_mult;

View File

@ -673,6 +673,7 @@ private:
(ParamBool<px4::params::MAV_HASH_CHK_EN>) _param_mav_hash_chk_en,
(ParamBool<px4::params::MAV_HB_FORW_EN>) _param_mav_hb_forw_en,
(ParamBool<px4::params::MAV_ODOM_LP>) _param_mav_odom_lp,
(ParamInt<px4::params::MAV_RADIO_TOUT>) _param_mav_radio_timeout,
(ParamInt<px4::params::SYS_HITL>) _param_sys_hitl
)

View File

@ -175,3 +175,17 @@ PARAM_DEFINE_INT32(MAV_HB_FORW_EN, 1);
* @group MAVLink
*/
PARAM_DEFINE_INT32(MAV_ODOM_LP, 0);
/**
* Timeout in seconds for the RADIO_STATUS reports coming in
*
* If the connected radio stops reporting RADIO_STATUS for a certain time,
* a warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow
* control is reset.
*
* @group MAVLink
* @unit s
* @min 1
* @max 250
*/
PARAM_DEFINE_INT32(MAV_RADIO_TOUT, 5);