From e14e5b9d73e8191fdfbda26c7110c8a1fe504d98 Mon Sep 17 00:00:00 2001 From: Claudio Micheli <claudio@auterion.com> Date: Tue, 19 Mar 2019 15:54:59 +0100 Subject: [PATCH] Commander: Changed COM_ONB_BOOT_T parameter to COM_OA_BOOT_T. Since the time out is only Obstacle-Avoidance related, the new naming is more self explanatory. Signed-off-by: Claudio Micheli <claudio@auterion.com> --- src/modules/commander/Commander.cpp | 2 +- src/modules/commander/Commander.hpp | 2 +- src/modules/commander/commander_params.c | 12 ++++++------ 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 3199ae8bb0..cab3998489 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -3967,7 +3967,7 @@ void Commander::data_link_check(bool &status_changed) //if avoidance never started if (_datalink_last_heartbeat_avoidance_system == 0 - && hrt_elapsed_time(&_datalink_last_heartbeat_avoidance_system) > _onboard_boot_timeout.get() * 1_s) { + && hrt_elapsed_time(&_datalink_last_heartbeat_avoidance_system) > _oa_boot_timeout.get() * 1_s) { if (!print_msg_once) { mavlink_log_critical(&mavlink_log_pub, "Avoidance system not available!"); print_msg_once = true; diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index 89a1c640c0..012cbd19b5 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -118,7 +118,7 @@ private: (ParamFloat<px4::params::COM_DISARM_LAND>) _disarm_when_landed_timeout, (ParamInt<px4::params::COM_OBS_AVOID>) _obs_avoid, - (ParamInt<px4::params::COM_ONB_BOOT_T>) _onboard_boot_timeout + (ParamInt<px4::params::COM_OA_BOOT_T>) _oa_boot_timeout ) diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index b5d442637e..f27e9f1883 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -798,7 +798,7 @@ PARAM_DEFINE_INT32(NAV_DLL_ACT, 0); PARAM_DEFINE_INT32(NAV_RCL_ACT, 2); /** - * Flag to enable obstacle avoidance + * Flag to enable obstacle avoidance. * * @boolean * @group Mission @@ -806,14 +806,14 @@ PARAM_DEFINE_INT32(NAV_RCL_ACT, 2); PARAM_DEFINE_INT32(COM_OBS_AVOID, 0); /** - * Set onboard controller bootup timeout + * Set avoidance system bootup timeout. * - * This parameter defines the bootup timeout. - * After the timeout, a mavlink message that tells the user that the avoidance system - * is not available is sent. + * The avoidance system running on the companion computer is expected to boot + * within this time and start providing trajectory points. + * If no avoidance system is detected a MAVLink warning message is sent. * @group Commander * @unit s * @min 0 * @max 200 */ -PARAM_DEFINE_INT32(COM_ONB_BOOT_T, 100); \ No newline at end of file +PARAM_DEFINE_INT32(COM_OA_BOOT_T, 100); \ No newline at end of file -- GitLab