From 30e763b6780061d70a14894e3e8b06e6a656f9b8 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Fri, 23 Aug 2024 07:20:54 -0700 Subject: [PATCH] Commander: lock down mav sys and comp id - keeps them as local params at init - only allow to set at init --- src/modules/commander/Commander.cpp | 27 ++++++++++++++------------- src/modules/commander/Commander.hpp | 2 -- 2 files changed, 14 insertions(+), 15 deletions(-) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 444f5b0c8dba..8e9f834c365c 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -698,11 +698,23 @@ Commander::Commander() : // default for vtol is rotary wing _vtol_vehicle_status.vehicle_vtol_state = vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC; - _param_mav_comp_id = param_find("MAV_COMP_ID"); - _param_mav_sys_id = param_find("MAV_SYS_ID"); + param_t param_mav_comp_id = param_find("MAV_COMP_ID"); + param_t param_mav_sys_id = param_find("MAV_SYS_ID"); _param_mav_type = param_find("MAV_TYPE"); _param_rc_map_fltmode = param_find("RC_MAP_FLTMODE"); + int32_t value_int32 = 0; + + // MAV_SYS_ID => vehicle_status.system_id + if ((param_mav_sys_id != PARAM_INVALID) && (param_get(param_mav_sys_id, &value_int32) == PX4_OK)) { + _vehicle_status.system_id = value_int32; + } + + // MAV_COMP_ID => vehicle_status.component_id + if ((param_mav_comp_id != PARAM_INVALID) && (param_get(param_mav_comp_id, &value_int32) == PX4_OK)) { + _vehicle_status.component_id = value_int32; + } + updateParameters(); } @@ -1682,22 +1694,11 @@ void Commander::updateParameters() int32_t value_int32 = 0; - // MAV_SYS_ID => vehicle_status.system_id - if ((_param_mav_sys_id != PARAM_INVALID) && (param_get(_param_mav_sys_id, &value_int32) == PX4_OK)) { - _vehicle_status.system_id = value_int32; - } - - // MAV_COMP_ID => vehicle_status.component_id - if ((_param_mav_comp_id != PARAM_INVALID) && (param_get(_param_mav_comp_id, &value_int32) == PX4_OK)) { - _vehicle_status.component_id = value_int32; - } - // MAV_TYPE -> vehicle_status.system_type if ((_param_mav_type != PARAM_INVALID) && (param_get(_param_mav_type, &value_int32) == PX4_OK)) { _vehicle_status.system_type = value_int32; } - _vehicle_status.avoidance_system_required = _param_com_obs_avoid.get(); _auto_disarm_killed.set_hysteresis_time_from(false, _param_com_kill_disarm.get() * 1_s); diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index d477585c0345..8d2cba1b9a82 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -323,8 +323,6 @@ class Commander : public ModuleBase, public ModuleParams perf_counter_t _preflight_check_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": preflight check")}; // optional parameters - param_t _param_mav_comp_id{PARAM_INVALID}; - param_t _param_mav_sys_id{PARAM_INVALID}; param_t _param_mav_type{PARAM_INVALID}; param_t _param_rc_map_fltmode{PARAM_INVALID};