diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 3199ae8bb029472a8bdb491236383474becfa65c..cab399848988ac31233f6a4a89716270a2375d10 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 89a1c640c0dbb73f9a2d3a70e056efaa5752b77a..012cbd19b5ac1f9a1b952afa02733475168a5f07 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 b5d442637e2004f7f3b780d05b4a50c2408be7fb..f27e9f1883d76a1756237db843d1c4f2e460fed5 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