Browse Source

AP_Param: added a flag for hidden parameters

gps-1.3.1
Andrew Tridgell 3 years ago committed by Peter Barker
parent
commit
10cbd3fd80
  1. 3
      libraries/AP_Param/AP_Param.cpp
  2. 5
      libraries/AP_Param/AP_Param.h

3
libraries/AP_Param/AP_Param.cpp

@ -1682,6 +1682,9 @@ AP_Param *AP_Param::next_group(const uint16_t vindex, const struct GroupInfo *gr @@ -1682,6 +1682,9 @@ AP_Param *AP_Param::next_group(const uint16_t vindex, const struct GroupInfo *gr
((AP_Int8 *)ret)->get() == 0) {
token->last_disabled = 1;
}
if (group_info[i].flags & AP_PARAM_FLAG_HIDDEN) {
continue;
}
return ret;
}
if (group_id(group_info, group_base, i, group_shift) == token->group_element) {

5
libraries/AP_Param/AP_Param.h

@ -72,13 +72,16 @@ @@ -72,13 +72,16 @@
// use.
#define AP_PARAM_FLAG_INTERNAL_USE_ONLY (1<<5)
// hide parameter from param download
#define AP_PARAM_FLAG_HIDDEN (1<<6)
// keep all flags before the FRAME tags
// vehicle and frame type flags, used to hide parameters when not
// relevent to a vehicle type. Use AP_Param::set_frame_type_flags() to
// enable parameters flagged in this way. frame type flags are stored
// in flags field, shifted by AP_PARAM_FRAME_TYPE_SHIFT.
#define AP_PARAM_FRAME_TYPE_SHIFT 6
#define AP_PARAM_FRAME_TYPE_SHIFT 7
// supported frame types for parameters
#define AP_PARAM_FRAME_COPTER (1<<0)

Loading…
Cancel
Save