|
|
|
@ -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) |
|
|
|
|