Skip to content

Commit

Permalink
Commander: lock down mav sys and comp id
Browse files Browse the repository at this point in the history
- keeps them as local params at init
- only allow to set at init
  • Loading branch information
mrpollo authored and dagar committed Aug 27, 2024
1 parent fe26cde commit 30e763b
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 15 deletions.
27 changes: 14 additions & 13 deletions src/modules/commander/Commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}

Expand Down Expand Up @@ -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);
Expand Down
2 changes: 0 additions & 2 deletions src/modules/commander/Commander.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -323,8 +323,6 @@ class Commander : public ModuleBase<Commander>, 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};

Expand Down

0 comments on commit 30e763b

Please sign in to comment.