From 3b5ef82193c69bafc9890ca0a16d87f16dbec460 Mon Sep 17 00:00:00 2001 From: Claudio Micheli <claudio@auterion.com> Date: Wed, 13 Mar 2019 14:33:02 +0100 Subject: [PATCH] Commander: Added COM_ONB_BOOT_T parameter. Since onboard controllers bootup times are hardware dependent, it makes sense to have the possibility to adapt timeout time according to the specific HW. Signed-off-by: Claudio Micheli <claudio@auterion.com> --- src/modules/commander/Commander.cpp | 5 +++-- src/modules/commander/Commander.hpp | 4 +++- src/modules/commander/commander_params.c | 16 +++++++++++++++- 3 files changed, 21 insertions(+), 4 deletions(-) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 23c899a9f0..a22e8a21c9 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -3964,14 +3964,15 @@ void Commander::data_link_check(bool &status_changed) if (status_flags.avoidance_system_required && !_onboard_controller_lost) { //if avoidance never started - if (_datalink_last_heartbeat_avoidance_system == 0 && hrt_elapsed_time(&_avoidance_system_not_started) > 10_s + if (_datalink_last_heartbeat_avoidance_system == 0 + && hrt_elapsed_time(&_avoidance_system_not_started) > _onboard_boot_timeout.get() * 1_s && avoidance_waiting_count < AVOIDANCE_MAX_TRIALS) { _avoidance_system_not_started = hrt_absolute_time(); mavlink_log_info(&mavlink_log_pub, "Waiting for avoidance system to start"); avoidance_waiting_count++; } else if (avoidance_waiting_count == AVOIDANCE_MAX_TRIALS) { - mavlink_log_critical(&mavlink_log_pub, "Avoidance system not responding. Try reboot vehicle."); + mavlink_log_critical(&mavlink_log_pub, "Avoidance not responding. Try reboot vehicle."); avoidance_waiting_count++; } diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index 82c3648385..89a1c640c0 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -117,7 +117,9 @@ private: (ParamInt<px4::params::COM_LOW_BAT_ACT>) _low_bat_action, (ParamFloat<px4::params::COM_DISARM_LAND>) _disarm_when_landed_timeout, - (ParamInt<px4::params::COM_OBS_AVOID>) _obs_avoid + (ParamInt<px4::params::COM_OBS_AVOID>) _obs_avoid, + (ParamInt<px4::params::COM_ONB_BOOT_T>) _onboard_boot_timeout + ) const int64_t POSVEL_PROBATION_MIN = 1_s; /**< minimum probation duration (usec) */ diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index e3b0313116..336bceafdc 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -805,4 +805,18 @@ PARAM_DEFINE_INT32(NAV_RCL_ACT, 2); * @reboot_required true * @group Mission */ -PARAM_DEFINE_INT32(COM_OBS_AVOID, 0); \ No newline at end of file +PARAM_DEFINE_INT32(COM_OBS_AVOID, 0); + +/** + * Set onboard controller bootup timeout + * + * This parameter defines the bootup timeout. + * After the timeout a mavlink message to warn the user that the system + * is still booting up is triggered. + * + * @group Commander + * @unit s + * @min 0 + * @max 120 + */ +PARAM_DEFINE_INT32(COM_ONB_BOOT_T, 15); \ No newline at end of file -- GitLab