ArduPilot开源代码之AP_Param

1. 源由

虽然ArduPilot功能强大,但是很多细节配置上,并非非常人性化,往往需要对配置参数进行配置。

而这些参数都是通过AP_Param这个类进行处理的,因此对于该类的一个整体了解,对于后续代码阅读以及数据保存相关操作可以更好的予以理解。

2. AP_Param类

如注释中所提及的,这个基础类主要提供变量名称定义和查找服务。

不过从代码角度看:

  1. 有很多很多方法函数:复杂度高
  2. 成员变量也不少:一个对象消耗不少内存资源

libraries/AP_Param/AP_Param.h

/// Base class for variables.
///
/// Provides naming and lookup services for variables.
///
class AP_Param
{
public:
    // the Info and GroupInfo structures are passed by the main
    // program in setup() to give information on how variables are
    // named and their location in memory
    struct GroupInfo {
        const char *name;
        ptrdiff_t offset; // offset within the object
        union {
            const struct GroupInfo *group_info;
            const struct GroupInfo **group_info_ptr; // when AP_PARAM_FLAG_INFO_POINTER is set in flags
            const float def_value;
            ptrdiff_t def_value_offset; // Default value offset from param object, when AP_PARAM_FLAG_DEFAULT_POINTER is set in flags
        };
        uint16_t flags;
        uint8_t idx;  // identifier within the group
        uint8_t type; // AP_PARAM_*
    };
    struct Info {
        const char *name;
        const void *ptr;    // pointer to the variable in memory
        union {
            const struct GroupInfo *group_info;
            const struct GroupInfo **group_info_ptr; // when AP_PARAM_FLAG_INFO_POINTER is set in flags
            const float def_value;
            ptrdiff_t def_value_offset; // Default value offset from param object, when AP_PARAM_FLAG_DEFAULT_POINTER is set in flags
        };
        uint16_t flags;
        uint16_t key; // k_param_*
        uint8_t type; // AP_PARAM_*
    };
    struct ConversionInfo {
        uint16_t old_key; // k_param_*
        uint32_t old_group_element; // index in old object
        enum ap_var_type type; // AP_PARAM_*
        const char *new_name;
    };

    // param default table element
    struct defaults_table_struct {
        const char *name;   // parameter name
        float value;        // parameter value
    };

    // called once at startup to setup the _var_info[] table. This
    // will also check the EEPROM header and re-initialise it if the
    // wrong version is found
    static bool setup();

    // constructor with var_info
    AP_Param(const struct Info *info)
    {
        _var_info = info;
        uint16_t i;
        for (i=0; info[i].type != AP_PARAM_NONE; i++) ;
        _num_vars = i;
#if AP_PARAM_DYNAMIC_ENABLED
        _num_vars_base = _num_vars;
#endif
        if (_singleton != nullptr) {
            AP_HAL::panic("AP_Param must be singleton");
        }
        _singleton = this;
    }

    // empty constructor
    AP_Param() {}

    // a token used for first()/next() state
    typedef struct {
        uint32_t key : 9;
        uint32_t idx : 4; // offset into array types
        uint32_t group_element : 18;
        uint32_t last_disabled : 1;
    } ParamToken;


    // nesting structure for recursive call states
    struct GroupNesting {
        static const uint8_t numlevels = 2;
        uint8_t level;
        const struct GroupInfo *group_ret[numlevels];
    };

    // return true if AP_Param has been initialised via setup()
    static bool initialised(void);

    // the 'group_id' of a element of a group is the 18 bit identifier
    // used to distinguish between this element of the group and other
    // elements of the same group. It is calculated using a bit shift per
    // level of nesting, so the first level of nesting gets 6 bits the 2nd
    // level gets the next 6 bits, and the 3rd level gets the last 6
    // bits. This limits groups to having at most 64 elements.
    static uint32_t group_id(const struct GroupInfo *grpinfo, uint32_t base, uint8_t i, uint8_t shift);

    /// Copy the variable's name, prefixed by any containing group name, to a
    /// buffer.
    ///
    /// If the variable has no name, the buffer will contain an empty string.
    ///
    /// Note that if the combination of names is larger than the buffer, the
    /// result in the buffer will be truncated.
    ///
    /// @param	token			token giving current variable
    /// @param	buffer			The destination buffer
    /// @param	bufferSize		Total size of the destination buffer.
    ///
    void copy_name_info(const struct AP_Param::Info *info,
                        const struct GroupInfo *ginfo,
                        const struct GroupNesting &group_nesting,
                        uint8_t idx, char *buffer, size_t bufferSize, bool force_scalar=false) const;

    /// Copy the variable's name, prefixed by any containing group name, to a
    /// buffer.
    ///
    /// Uses token to look up AP_Param::Info for the variable
    void copy_name_token(const ParamToken &token, char *buffer, size_t bufferSize, bool force_scalar=false) const;

    /// Find a variable by name.
    ///
    /// If the variable has no name, it cannot be found by this interface.
    ///
    /// @param  name            The full name of the variable to be found.
    /// @param  flags           If non-null will be filled with parameter flags
    /// @return                 A pointer to the variable, or nullptr if
    ///                         it does not exist.
    ///
    static AP_Param * find(const char *name, enum ap_var_type *ptype, uint16_t *flags = nullptr);

    /// set a default value by name
    ///
    /// @param  name            The full name of the variable to be found.
    /// @param  value           The default value
    /// @return                 true if the variable is found
    static bool set_default_by_name(const char *name, float value);

    /// set parameter defaults from a defaults_table_struct
    ///
    /// @param table            pointer to array of defaults_table_struct structures
    /// @param count            number of elements in table array
    static void set_defaults_from_table(const struct defaults_table_struct *table, uint8_t count);

    /// set a value by name
    ///
    /// @param  name            The full name of the variable to be found.
    /// @param  value           The new value
    /// @return                 true if the variable is found
    static bool set_by_name(const char *name, float value);

    /// gat a value by name, used by scripting
    ///
    /// @param  name            The full name of the variable to be found.
    /// @param  value           A reference to the variable
    /// @return                 true if the variable is found
    static bool get(const char *name, float &value);

    /// set and save a value by name
    ///
    /// @param  name            The full name of the variable to be found.
    /// @param  value           The new value
    /// @return                 true if the variable is found
    static bool set_and_save_by_name(const char *name, float value);
    static bool set_and_save_by_name_ifchanged(const char *name, float value);

    /// Find a variable by index.
    ///
    ///
    /// @param  idx             The index of the variable
    /// @return                 A pointer to the variable, or nullptr if
    ///                         it does not exist.
    ///
    static AP_Param * find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token);

    // by-name equivalent of find_by_index()
    static AP_Param* find_by_name(const char* name, enum ap_var_type *ptype, ParamToken *token);

    /// Find a variable by pointer
    ///
    ///
    /// @param  p               Pointer to variable
    /// @return                 key for variable
    static bool find_key_by_pointer_group(const void *ptr, uint16_t vindex, const struct GroupInfo *group_info,
                                          ptrdiff_t offset, uint16_t &key);
    static bool find_key_by_pointer(const void *ptr, uint16_t &key);

    /// Find key of top level group variable by pointer
    ///
    ///
    /// @param  p               Pointer to variable
    /// @return                 key for variable
    static bool find_top_level_key_by_pointer(const void *ptr, uint16_t &key);


    /// Find a object in the top level var_info table
    ///
    /// If the variable has no name, it cannot be found by this interface.
    ///
    /// @param  name            The full name of the variable to be found.
    ///
    static AP_Param * find_object(const char *name);

    /// Notify GCS of current parameter value
    ///
    void notify() const;

    /// Save the current value of the variable to storage, synchronous API
    ///
    /// @param  force_save     If true then force save even if default
    ///
    /// @return                True if the variable was saved successfully.
    ///
    void save_sync(bool force_save, bool send_to_gcs);

    /// flush all pending parameter saves
    /// used on reboot
    static void flush(void);

    /// Save the current value of the variable to storage, async interface
    ///
    /// @param  force_save     If true then force save even if default
    ///
    void save(bool force_save=false);

    /// Load the variable from EEPROM.
    ///
    /// @return                True if the variable was loaded successfully.
    ///
    bool load(void);

    /// Load all variables from EEPROM
    ///
    /// This function performs a best-efforts attempt to load all
    /// of the variables from EEPROM.  If some fail to load, their
    /// values will remain as they are.
    ///
    /// @return                False if any variable failed to load
    ///
    static bool load_all();

    // returns storage space used:
    static uint16_t storage_used() { return sentinal_offset; }

    // returns storage space :
    static uint16_t storage_size() { return _storage.size(); }

    /// reoad the hal.util defaults file. Called after pointer parameters have been allocated
    ///
    static void reload_defaults_file(bool last_pass);

    static void load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info);

    // set a AP_Param variable to a specified value
    static void         set_value(enum ap_var_type type, void *ptr, float def_value);

    /*
      set a parameter to a float
    */
    void set_float(float value, enum ap_var_type var_type);

    // load default values for scalars in a group
    static void         setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info);

    // set a value directly in an object.
    // return true if the name was found and set, else false.
    // This should only be used by example code, not by mainline vehicle code
    static bool set_object_value(const void *object_pointer,
                                 const struct GroupInfo *group_info,
                                 const char *name, float value);

    // load default values for all scalars in the main sketch. This
    // does not recurse into the sub-objects    
    static void         setup_sketch_defaults(void);

    // find an old parameter and return it.
    static bool find_old_parameter(const struct ConversionInfo *info, AP_Param *value);

    // convert old vehicle parameters to new object parameters
    static void         convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags=0);

    /*
      convert width of a parameter, allowing update to wider scalar
      values without changing the parameter indexes. This will return
      true if the parameter was converted from an old parameter value
    */
    bool convert_parameter_width(ap_var_type old_ptype);
    
    // convert a single parameter with scaling
    enum {
        CONVERT_FLAG_REVERSE=1, // handle _REV -> _REVERSED conversion
        CONVERT_FLAG_FORCE=2    // store new value even if configured in eeprom already
    };
    static void         convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags=0);

    // move all parameters from a class to a new location
    // is_top_level: Is true if the class had its own top level key, param_key. It is false if the class was a subgroup
    static void         convert_class(uint16_t param_key, void *object_pointer,
                                        const struct AP_Param::GroupInfo *group_info,
                                        uint16_t old_index, uint16_t old_top_element, bool is_top_level);

    /*
      fetch a parameter value based on the index within a group. This
      is used to find the old value of a parameter that has been
      removed from an object.
    */
    static bool get_param_by_index(void *obj_ptr, uint8_t idx, ap_var_type old_ptype, void *pvalue);
    
    /// Erase all variables in EEPROM.
    ///
    static void         erase_all(void);

    /// Returns the first variable
    ///
    /// @return             The first variable in _var_info, or nullptr if
    ///                     there are none.
    ///
    static AP_Param *      first(ParamToken *token, enum ap_var_type *ptype, float *default_val = nullptr);

    /// Returns the next variable in _var_info, recursing into groups
    /// as needed
    static AP_Param *      next(ParamToken *token, enum ap_var_type *ptype) { return  next(token, ptype, false); }
    static AP_Param *      next(ParamToken *token, enum ap_var_type *ptype, bool skip_disabled, float *default_val = nullptr);

    /// Returns the next scalar variable in _var_info, recursing into groups
    /// as needed
    static AP_Param *       next_scalar(ParamToken *token, enum ap_var_type *ptype, float *default_val = nullptr);

    /// get the size of a type in bytes
    static uint8_t				type_size(enum ap_var_type type);

    /// cast a variable to a float given its type
    float                   cast_to_float(enum ap_var_type type) const;

    // check var table for consistency
    static void             check_var_info(void);

    // return true if the parameter is configured
    bool configured(void) const;

    // return true if the parameter is read-only
    bool is_read_only(void) const;

    // return the persistent top level key for the ParamToken key
    static uint16_t get_persistent_key(uint16_t key) { return var_info(key).key; }
    
    // count of parameters in tree
    static uint16_t count_parameters(void);

    // invalidate parameter count
    static void invalidate_count(void);

    static void set_hide_disabled_groups(bool value) { _hide_disabled_groups = value; }

    // set frame type flags. Used to unhide frame specific parameters
    static void set_frame_type_flags(uint16_t flags_to_set) {
        invalidate_count();
        _frame_type_flags |= flags_to_set;
    }

    // check if a given frame type should be included
    static bool check_frame_type(uint16_t flags);

#if AP_PARAM_KEY_DUMP
    /// print the value of all variables
    static void         show_all(AP_HAL::BetterStream *port, bool showKeyValues=false);

    /// print the value of one variable
    static void         show(const AP_Param *param, 
                             const char *name,
                             enum ap_var_type ptype, 
                             AP_HAL::BetterStream *port);

    /// print the value of one variable
    static void         show(const AP_Param *param, 
                             const ParamToken &token,
                             enum ap_var_type ptype, 
                             AP_HAL::BetterStream *port);
#endif // AP_PARAM_KEY_DUMP

    static AP_Param *get_singleton() { return _singleton; }

#if AP_PARAM_DYNAMIC_ENABLED
    // allow for dynamically added parameter tables from scripts
    static bool add_table(uint8_t key, const char *prefix, uint8_t num_params);
    static bool add_param(uint8_t key, uint8_t param_num, const char *pname, float default_value);
    static bool load_int32(uint16_t key, uint32_t group_element, int32_t &value);
#endif

    static bool load_defaults_file(const char *filename, bool last_pass);

protected:

    // store default value in linked list
    static void add_default(AP_Param *ap, float v);

private:
    static AP_Param *_singleton;

    /// EEPROM header
    ///
    /// This structure is placed at the head of the EEPROM to indicate
    /// that the ROM is formatted for AP_Param.
    ///
    struct EEPROM_header {
        uint8_t magic[2];
        uint8_t revision;
        uint8_t spare;
    };
    static_assert(sizeof(struct EEPROM_header) == 4, "Bad EEPROM_header size!");

    static uint16_t sentinal_offset;

/* This header is prepended to a variable stored in EEPROM.
 *  The meaning is as follows:
 *
 *  - key: the k_param enum value from Parameter.h in the sketch
 *
 *  - group_element: This is zero for top level parameters. For
 *                   parameters stored within an object this is divided
 *                   into 3 lots of 6 bits, allowing for three levels
 *                   of object to be stored in the eeprom
 *
 *  - type: the ap_var_type value for the variable
 */
    struct Param_header {
        // to get 9 bits for key we needed to split it into two parts to keep binary compatibility
        uint32_t key_low : 8;
        uint32_t type : 5;
        uint32_t key_high : 1;
        uint32_t group_element : 18;
    };
    static_assert(sizeof(struct Param_header) == 4, "Bad Param_header size!");

    // number of bits in each level of nesting of groups
    static const uint8_t        _group_level_shift = 6;
    static const uint8_t        _group_bits  = 18;

    static const uint16_t       _sentinal_key   = 0x1FF;
    static const uint8_t        _sentinal_type  = 0x1F;
    static const uint8_t        _sentinal_group = 0xFF;

    static uint16_t             _frame_type_flags;

    /*
      structure for built-in defaults file that can be modified using apj_tool.py
     */
#if AP_PARAM_MAX_EMBEDDED_PARAM > 0
    struct PACKED param_defaults_struct {
        char magic_str[8];
        uint8_t param_magic[8];
        uint16_t max_length;
        volatile uint16_t length;
        volatile char data[AP_PARAM_MAX_EMBEDDED_PARAM];
    };
    static const param_defaults_struct param_defaults_data;
#endif


    static void                 check_group_info(const struct GroupInfo *group_info, uint16_t *total_size, 
                                                 uint8_t max_bits, uint8_t prefix_length);
    static bool                 duplicate_key(uint16_t vindex, uint16_t key);

    static bool adjust_group_offset(uint16_t vindex, const struct GroupInfo &group_info, ptrdiff_t &new_offset);
    static bool get_base(const struct Info &info, ptrdiff_t &base);

    /// get group_info pointer based on flags
    static const struct GroupInfo *get_group_info(const struct GroupInfo &ginfo);

    /// get group_info pointer based on flags
    static const struct GroupInfo *get_group_info(const struct Info &ginfo);

    const struct Info *         find_var_info_group(
                                    const struct GroupInfo *    group_info,
                                    uint16_t                    vindex,
                                    uint32_t                    group_base,
                                    uint8_t                     group_shift,
                                    ptrdiff_t                   group_offset,
                                    uint32_t *                  group_element,
                                    const struct GroupInfo *   &group_ret,
                                    struct GroupNesting        &group_nesting,
                                    uint8_t *                   idx) const;
    const struct Info *         find_var_info(
                                    uint32_t *                group_element,
                                    const struct GroupInfo *  &group_ret,
                                    struct GroupNesting       &group_nesting,
                                    uint8_t *                 idx) const;
    const struct Info *			find_var_info_token(const ParamToken &token,
                                                    uint32_t *                 group_element,
                                                    const struct GroupInfo *  &group_ret,
                                                    struct GroupNesting       &group_nesting,
                                                    uint8_t *                  idx) const;
    static const struct Info *  find_by_header_group(
                                    struct Param_header phdr, void **ptr,
                                    uint16_t vindex,
                                    const struct GroupInfo *group_info,
                                    uint32_t group_base,
                                    uint8_t group_shift,
                                    ptrdiff_t group_offset);
    static const struct Info *  find_by_header(
                                    struct Param_header phdr,
                                    void **ptr);
    void                        add_vector3f_suffix(
                                    char *buffer,
                                    size_t buffer_size,
                                    uint8_t idx) const;
    static AP_Param *           find_group(
                                    const char *name,
                                    uint16_t vindex,
                                    ptrdiff_t group_offset,
                                    const struct GroupInfo *group_info,
                                    enum ap_var_type *ptype);
    static void                 write_sentinal(uint16_t ofs);
    static uint16_t             get_key(const Param_header &phdr);
    static void                 set_key(Param_header &phdr, uint16_t key);
    static bool                 is_sentinal(const Param_header &phrd);
    static bool                 scan(
                                    const struct Param_header *phdr,
                                    uint16_t *pofs);
    static void                 eeprom_write_check(
                                    const void *ptr,
                                    uint16_t ofs,
                                    uint8_t size);
    static AP_Param *           next_group(
                                    const uint16_t vindex,
                                    const struct GroupInfo *group_info,
                                    bool *found_current,
                                    const uint32_t group_base,
                                    const uint8_t group_shift,
                                    const ptrdiff_t group_offset,
                                    ParamToken *token,
                                    enum ap_var_type *ptype,
                                    bool skip_disabled,
                                    float *default_val);

    // find a default value given a pointer to a default value in flash
    static float get_default_value(const AP_Param *object_ptr, const struct GroupInfo &info);
    static float get_default_value(const AP_Param *object_ptr, const struct Info &info);

    static bool parse_param_line(char *line, char **vname, float &value, bool &read_only);

    /*
      load a parameter defaults file. This happens as part of load_all()
     */
    static bool count_defaults_in_file(const char *filename, uint16_t &num_defaults);
    static bool read_param_defaults_file(const char *filename, bool last_pass);

    /*
      load defaults from embedded parameters
     */
    static bool count_embedded_param_defaults(uint16_t &count);
    static void load_embedded_param_defaults(bool last_pass);

    // return true if the parameter is configured in the defaults file
    bool configured_in_defaults_file(bool &read_only) const;

    // return true if the parameter is configured in EEPROM/FRAM
    bool configured_in_storage(void) const;

    // send a parameter to all GCS instances
    void send_parameter(const char *name, enum ap_var_type param_header_type, uint8_t idx) const;

    static StorageAccess        _storage;
    static StorageAccess        _storage_bak;
    static uint16_t             _num_vars;
    static uint16_t             _parameter_count;
    static uint16_t             _count_marker;
    static uint16_t             _count_marker_done;
    static HAL_Semaphore        _count_sem;
    static const struct Info *  _var_info;

#if AP_PARAM_DYNAMIC_ENABLED
    // allow for a dynamically allocated var table
    static uint16_t             _num_vars_base;
    static struct Info *        _var_info_dynamic;
    static const struct AP_Param::Info &var_info(uint16_t i) {
        return i<_num_vars_base? _var_info[i] : _var_info_dynamic[i-_num_vars_base];
    }
    static uint8_t _dynamic_table_sizes[AP_PARAM_MAX_DYNAMIC];
#else
    // simple static var table in flash
    static const struct Info &var_info(uint16_t i) {
        return _var_info[i];
    }
#endif

    /*
      list of overridden values from load_defaults_file()
    */
    struct param_override {
        const AP_Param *object_ptr;
        float value;
        bool read_only; // param is marked @READONLY
    };
    static struct param_override *param_overrides;
    static uint16_t num_param_overrides;
    static uint16_t num_read_only;

    // values filled into the EEPROM header
    static const uint8_t        k_EEPROM_magic0      = 0x50;
    static const uint8_t        k_EEPROM_magic1      = 0x41; ///< "AP"
    static const uint8_t        k_EEPROM_revision    = 6; ///< current format revision

    static bool _hide_disabled_groups;

    // support for background saving of parameters. We pack it to reduce memory for the
    // queue
    struct PACKED param_save {
        AP_Param *param;
        bool force_save;
    };
    static ObjectBuffer_TS<struct param_save> save_queue;
    static bool registered_save_handler;

    // background function for saving parameters
    void save_io_handler(void);

    // Store default values from add_default() calls in linked list
    struct defaults_list {
        AP_Param *ap;
        float val;
        defaults_list *next;
    };
    static defaults_list *default_list;
    static void check_default(AP_Param *ap, float *default_value);
};

3. AP_Param主要方法

总体来看,AP_Param类还是比较复杂的,这里只是做一个入门的初步介绍,更多详细且具体的功能还是需要实际应用过程中不断摸索和了解。

注:这里开列的主要是公共/保护的方法。

3.1 AP_Param

构造函数,使用var_info数组初始化

注:这里如果不是数组或者数组越界,就比较糟糕,因此需要开发设计确保。

    // constructor with var_info
    AP_Param(const struct Info *info)
    {
        _var_info = info;
        uint16_t i;
        for (i=0; info[i].type != AP_PARAM_NONE; i++) ;
        _num_vars = i;
#if AP_PARAM_DYNAMIC_ENABLED
        _num_vars_base = _num_vars;
#endif
        if (_singleton != nullptr) {
            AP_HAL::panic("AP_Param must be singleton");
        }
        _singleton = this;
    }

    struct Info {
        const char *name;
        const void *ptr;    // pointer to the variable in memory
        union {
            const struct GroupInfo *group_info;
            const struct GroupInfo **group_info_ptr; // when AP_PARAM_FLAG_INFO_POINTER is set in flags
            const float def_value;
            ptrdiff_t def_value_offset; // Default value offset from param object, when AP_PARAM_FLAG_DEFAULT_POINTER is set in flags
        };
        uint16_t flags;
        uint16_t key; // k_param_*
        uint8_t type; // AP_PARAM_*
    };

空析构函数

    // empty constructor
    AP_Param() {}

3.2 setup

启动时运行一次参数检查,检查EEPROM头(错误则重新初始化),同步_var_info[]表。

bool AP_Param::setup(void)
{
    struct EEPROM_header hdr {};
    struct EEPROM_header hdr2 {};

    // check the header
    _storage.read_block(&hdr, 0, sizeof(hdr));
    _storage_bak.read_block(&hdr2, 0, sizeof(hdr2));
    if (hdr.magic[0] != k_EEPROM_magic0 ||
        hdr.magic[1] != k_EEPROM_magic1 ||
        hdr.revision != k_EEPROM_revision) {
        if (hdr2.magic[0] == k_EEPROM_magic0 &&
            hdr2.magic[1] == k_EEPROM_magic1 &&
            hdr2.revision == k_EEPROM_revision &&
            _storage.copy_area(_storage_bak)) {
            // restored from backup //从备份数据恢复
            INTERNAL_ERROR(AP_InternalError::error_t::params_restored);
            return true;
        }
        // header doesn't match. We can't recover any variables. Wipe
        // the header and setup the sentinal directly after the header
        Debug("bad header in setup - erasing");
        erase_all(); //最坏情况
    }

    // ensure that backup is in sync with primary
    _storage_bak.copy_area(_storage);

    return true;
}

3.3 initialised

初始化判断:是否已经完成初始化,默认成员变量为空。

真:已初始化
假:未初始化

bool AP_Param::initialised(void)
{
    return _var_info != nullptr;
}

3.4 group_id

group_id是用于区分该组的该元素和同一组的其他元素的18位标识符,唯一元素标识符。

uint32_t AP_Param::group_id(const struct GroupInfo *grpinfo, uint32_t base, uint8_t i, uint8_t shift)
{
    if (grpinfo[i].idx == 0 && shift != 0 && !(grpinfo[i].flags & AP_PARAM_FLAG_NO_SHIFT)) {
        /*
          this is a special case for a bug in the original design. An
          idx of 0 shifted by n bits is still zero, which makes it
          indistinguishable from a different parameter. This can lead
          to parameter loops. We use index 63 for that case.
        */
        return base + (63U<<shift);
    }
    return base + (grpinfo[i].idx<<shift);
}

3.5 copy_name_info

通过<info,group_nesting>获取变量名称,将变量的名称(包含前缀组名)复制到缓冲区。如果变量没有名称,则缓冲区将包含一个空字符串。如果名称的组合大于缓冲区,则缓冲区中的结果将被截断。

void AP_Param::copy_name_info(const struct AP_Param::Info *info,
                              const struct GroupInfo *ginfo,
                              const struct GroupNesting &group_nesting,
                              uint8_t idx, char *buffer, size_t buffer_size, bool force_scalar) const
{
    strncpy(buffer, info->name, buffer_size);
    for (uint8_t i=0; i<group_nesting.level; i++) {
        uint8_t len = strnlen(buffer, buffer_size);
        if (len < buffer_size) {
            strncpy(&buffer[len], group_nesting.group_ret[i]->name, buffer_size-len);
        }
    }
    if (ginfo != nullptr) {
        uint8_t len = strnlen(buffer, buffer_size);
        if (len < buffer_size) {
            strncpy(&buffer[len], ginfo->name, buffer_size-len);
        }
        if ((force_scalar || idx != 0) && AP_PARAM_VECTOR3F == ginfo->type) {
            // the caller wants a specific element in a Vector3f
            add_vector3f_suffix(buffer, buffer_size, idx);
        }
    } else if ((force_scalar || idx != 0) && AP_PARAM_VECTOR3F == info->type) {
        add_vector3f_suffix(buffer, buffer_size, idx);
    }
}

3.6 copy_name_token

通过获取变量名称。使用token获取变量名称,最终调用copy_name_info

void AP_Param::copy_name_token(const ParamToken &token, char *buffer, size_t buffer_size, bool force_scalar) const
{
    uint32_t group_element;
    const struct GroupInfo *ginfo;
    struct GroupNesting group_nesting {};
    uint8_t idx;
    const struct AP_Param::Info *info = find_var_info_token(token, &group_element, ginfo, group_nesting, &idx);
    if (info == nullptr) {
        *buffer = 0;
        Debug("no info found");
        return;
    }
    copy_name_info(info, ginfo, group_nesting, idx, buffer, buffer_size, force_scalar);
}

3.7 find

通过名称查找变量。

AP_Param *
AP_Param::find(const char *name, enum ap_var_type *ptype, uint16_t *flags)
{
    for (uint16_t i=0; i<_num_vars; i++) {
        const auto &info = var_info(i);
        uint8_t type = info.type;
        if (type == AP_PARAM_GROUP) {
            uint8_t len = strnlen(info.name, AP_MAX_NAME_SIZE);
            if (strncmp(name, info.name, len) != 0) {
                continue;
            }
            const struct GroupInfo *group_info = get_group_info(info);
            if (group_info == nullptr) {
                continue;
            }
            AP_Param *ap = find_group(name + len, i, 0, group_info, ptype);
            if (ap != nullptr) {
                if (flags != nullptr) {
                    uint32_t group_element = 0;
                    const struct GroupInfo *ginfo;
                    struct GroupNesting group_nesting {};
                    uint8_t idx;
                    ap->find_var_info(&group_element, ginfo, group_nesting, &idx);
                    if (ginfo != nullptr) {
                        *flags = ginfo->flags;
                    }
                }
                return ap;
            }
            // we continue looking as we want to allow top level
            // parameter to have the same prefix name as group
            // parameters, for example CAM_P_G
        } else if (strcasecmp(name, info.name) == 0) {
            *ptype = (enum ap_var_type)type;
            ptrdiff_t base;
            if (!get_base(info, base)) {
                return nullptr;
            }
            return (AP_Param *)base;
        }
    }
    return nullptr;
}

3.8 set_default_by_name

通过变量名称设置参数值。设置变量对应类型AP_PARAM_INT8/AP_PARAM_INT16/AP_PARAM_INT32/AP_PARAM_FLOAT的参数值。

bool AP_Param::set_default_by_name(const char *name, float value)
{
    enum ap_var_type vtype;
    AP_Param *vp = find(name, &vtype);
    if (vp == nullptr) {
        return false;
    }
    switch (vtype) {
    case AP_PARAM_INT8:
        ((AP_Int8 *)vp)->set_default(value);
        return true;
    case AP_PARAM_INT16:
        ((AP_Int16 *)vp)->set_default(value);
        return true;
    case AP_PARAM_INT32:
        ((AP_Int32 *)vp)->set_default(value);
        return true;
    case AP_PARAM_FLOAT:
        ((AP_Float *)vp)->set_default(value);
        return true;
    default:
        break;
    }
    // not a supported type
    return false;
}

3.9 set_defaults_from_table

通过变量名称表设置参数值。

void AP_Param::set_defaults_from_table(const struct defaults_table_struct *table, uint8_t count)
{
    for (uint8_t i=0; i<count; i++) {
        if (!AP_Param::set_default_by_name(table[i].name, table[i].value)) {
            AP_BoardConfig::config_error("param deflt fail:%s", table[i].name);
        }
    }
}

3.10 set_by_name

根据变量名称设置参数值。

bool AP_Param::set_by_name(const char *name, float value)
{
    enum ap_var_type vtype;
    AP_Param *vp = find(name, &vtype);
    if (vp == nullptr) {
        return false;
    }
    switch (vtype) {
    case AP_PARAM_INT8:
        ((AP_Int8 *)vp)->set(value);
        return true;
    case AP_PARAM_INT16:
        ((AP_Int16 *)vp)->set(value);
        return true;
    case AP_PARAM_INT32:
        ((AP_Int32 *)vp)->set(value);
        return true;
    case AP_PARAM_FLOAT:
        ((AP_Float *)vp)->set(value);
        return true;
    default:
        break;
    }
    // not a supported type
    return false;
}

3.11 get

通过变量名称获取参数值。

bool AP_Param::get(const char *name, float &value)
{
    enum ap_var_type vtype;
    AP_Param *vp = find(name, &vtype);
    if (vp == nullptr) {
        return false;
    }
    switch (vtype) {
    case AP_PARAM_INT8:
        value = ((AP_Int8 *)vp)->get();
        break;
    case AP_PARAM_INT16:
        value = ((AP_Int16 *)vp)->get();
        break;

    case AP_PARAM_INT32:
        value = ((AP_Int32 *)vp)->get();
        break;

    case AP_PARAM_FLOAT:
        value = ((AP_Float *)vp)->get();
        break;

    default:
        // not a supported type
        return false;
    }
    return true;
}

3.12 set_and_save_by_name

通过名称设置并保存参数值。

bool AP_Param::set_and_save_by_name(const char *name, float value)
{
    enum ap_var_type vtype;
    AP_Param *vp = find(name, &vtype);
    if (vp == nullptr) {
        return false;
    }
    switch (vtype) {
    case AP_PARAM_INT8:
        ((AP_Int8 *)vp)->set_and_save(value);
        return true;
    case AP_PARAM_INT16:
        ((AP_Int16 *)vp)->set_and_save(value);
        return true;
    case AP_PARAM_INT32:
        ((AP_Int32 *)vp)->set_and_save(value);
        return true;
    case AP_PARAM_FLOAT:
        ((AP_Float *)vp)->set_and_save(value);
        return true;
    default:
        break;
    }
    // not a supported type
    return false;
}

3.13 set_and_save_by_name_ifchanged

如果参数值发生变更,保存参数值。

bool AP_Param::set_and_save_by_name_ifchanged(const char *name, float value)
{
    enum ap_var_type vtype;
    AP_Param *vp = find(name, &vtype);
    if (vp == nullptr) {
        return false;
    }
    switch (vtype) {
    case AP_PARAM_INT8:
        ((AP_Int8 *)vp)->set_and_save_ifchanged(value);
        return true;
    case AP_PARAM_INT16:
        ((AP_Int16 *)vp)->set_and_save_ifchanged(value);
        return true;
    case AP_PARAM_INT32:
        ((AP_Int32 *)vp)->set_and_save_ifchanged(value);
        return true;
    case AP_PARAM_FLOAT:
        ((AP_Float *)vp)->set_and_save_ifchanged(value);
        return true;
    default:
        break;
    }
    // not a supported type
    return false;
}

3.14 find_by_index

通过<idx, ptype, token>查找参数变量。

AP_Param *
AP_Param::find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token)
{
    AP_Param *ap;
    uint16_t count=0;
    for (ap=AP_Param::first(token, ptype);
         ap && count < idx;
         ap=AP_Param::next_scalar(token, ptype)) {
        count++;
    }
    return ap;    
}

3.15 find_by_name

通过<name, ptype, token>查找变量。

AP_Param* AP_Param::find_by_name(const char* name, enum ap_var_type *ptype, ParamToken *token)
{
    AP_Param *ap;
    uint16_t count = 0;
    for (ap = AP_Param::first(token, ptype);
         ap && *ptype != AP_PARAM_GROUP && *ptype != AP_PARAM_NONE;
         ap = AP_Param::next_scalar(token, ptype)) {
        int32_t ret = strncasecmp(name, var_info(token->key).name, AP_MAX_NAME_SIZE);
        if (ret >= 0) {
            char buf[AP_MAX_NAME_SIZE];
            ap->copy_name_token(*token, buf, AP_MAX_NAME_SIZE);
            if (strncasecmp(name, buf, AP_MAX_NAME_SIZE) == 0) {
                break;
            }
        }
        count++;
    }
    return ap;
}

3.16 find_key_by_pointer_group

通过<ptr, vindex, group_info, offset>指针查找变量并返回key值。

bool AP_Param::find_key_by_pointer_group(const void *ptr, uint16_t vindex,
                                         const struct GroupInfo *group_info,
                                         ptrdiff_t offset, uint16_t &key)
{
    for (uint8_t i=0; group_info[i].type != AP_PARAM_NONE; i++) {
        if (group_info[i].type != AP_PARAM_GROUP) {
            continue;
        }
        ptrdiff_t base;
        if (!get_base(var_info(vindex), base)) {
            continue;
        }
        if (group_info[i].flags & AP_PARAM_FLAG_POINTER) {
            if (ptr == *(void **)(base+group_info[i].offset+offset)) {
                key = var_info(vindex).key;
                return true;
            }
        } else if (ptr == (void *)(base+group_info[i].offset+offset)) {
            key = var_info(vindex).key;
            return true;
        }
        ptrdiff_t new_offset = offset;
        if (!adjust_group_offset(vindex, group_info[i], new_offset)) {
            continue;
        }
        const struct GroupInfo *ginfo = get_group_info(group_info[i]);
        if (ginfo == nullptr) {
            continue;
        }
        if (find_key_by_pointer_group(ptr, vindex, ginfo, new_offset, key)) {
            return true;
        }
    }
    return false;
}

3.17 find_key_by_pointer

通过指针直接查找变量并返回key值。

bool AP_Param::find_key_by_pointer(const void *ptr, uint16_t &key)
{
    for (uint16_t i=0; i<_num_vars; i++) {
        const auto &info = var_info(i);
        if (info.type != AP_PARAM_GROUP) {
            continue;
        }
        if ((info.flags & AP_PARAM_FLAG_POINTER) &&
            ptr == *(void **)info.ptr) {
            key = info.key;
            return true;
        }
        ptrdiff_t offset = 0;
        const struct GroupInfo *ginfo = get_group_info(info);
        if (ginfo == nullptr) {
            continue;
        }
        if (find_key_by_pointer_group(ptr, i, ginfo, offset, key)) {
            return true;
        }
    }
    return false;
}

3.18 find_top_level_key_by_pointer

通过指针查找顶级组参数的键。

bool AP_Param::find_top_level_key_by_pointer(const void *ptr, uint16_t &key)
{
    for (uint16_t i=0; i<_num_vars; i++) {
        const auto &info = var_info(i);
        if (info.type != AP_PARAM_GROUP) {
            continue;
        }
        if (ptr == (void **)info.ptr) {
            key = info.key;
            return true;
        }
    }
    return false;
}

3.19 find_object

通过变量名称查找变量。

AP_Param *
AP_Param::find_object(const char *name)
{
    for (uint16_t i=0; i<_num_vars; i++) {
        const auto &info = var_info(i);
        if (strcasecmp(name, info.name) == 0) {
            ptrdiff_t base;
            if (!get_base(info, base)) {
                return nullptr;
            }
            return (AP_Param *)base;
        }
    }
    return nullptr;
}

3.20 notify

将参数的当前值通知地面控制系统。

void AP_Param::notify() const {
    uint32_t group_element = 0;
    const struct GroupInfo *ginfo;
    struct GroupNesting group_nesting {};
    uint8_t idx;

    const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx);
    if (info == nullptr) {
        // this is probably very bad
        return;
    }

    char name[AP_MAX_NAME_SIZE+1];
    copy_name_info(info, ginfo, group_nesting, idx, name, sizeof(name), true);

    uint32_t param_header_type;
    if (ginfo != nullptr) {
        param_header_type = ginfo->type;
    } else {
        param_header_type = info->type;
    }

    send_parameter(name, (enum ap_var_type)param_header_type, idx);
}

3.21 save_sync

将变量同步保存到HAL存储。

void AP_Param::save_sync(bool force_save, bool send_to_gcs)
{
    uint32_t group_element = 0;
    const struct GroupInfo *ginfo;
    struct GroupNesting group_nesting {};
    uint8_t idx;
    const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx);
    const AP_Param *ap;

    if (info == nullptr) {
        // we don't have any info on how to store it
        return;
    }

    struct Param_header phdr;

    // create the header we will use to store the variable
    if (ginfo != nullptr) {
        phdr.type = ginfo->type;
        if (ginfo->flags & AP_PARAM_FLAG_HIDDEN) {
            send_to_gcs = false;
        }
    } else {
        phdr.type = info->type;
        if (info->flags & AP_PARAM_FLAG_HIDDEN) {
            send_to_gcs = false;
        }
    }
    set_key(phdr, info->key);
    phdr.group_element = group_element;

    ap = this;
    if (phdr.type != AP_PARAM_VECTOR3F && idx != 0) {
        // only vector3f can have non-zero idx for now
        return;
    }
    if (idx != 0) {
        ap = (const AP_Param *)((ptrdiff_t)ap) - (idx*sizeof(float));
    }

    if (phdr.type == AP_PARAM_INT8 && ginfo != nullptr && (ginfo->flags & AP_PARAM_FLAG_ENABLE)) {
        // clear cached parameter count
        invalidate_count();
    }
    
    char name[AP_MAX_NAME_SIZE+1];
    copy_name_info(info, ginfo, group_nesting, idx, name, sizeof(name), true);

    // scan EEPROM to find the right location
    uint16_t ofs;
    if (scan(&phdr, &ofs)) {
        // found an existing copy of the variable
        eeprom_write_check(ap, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
        if (send_to_gcs) {
            send_parameter(name, (enum ap_var_type)phdr.type, idx);
        }
        return;
    }
    if (ofs == (uint16_t) ~0) {
        return;
    }

    // if the value is the default value then don't save
    if (phdr.type <= AP_PARAM_FLOAT) {
        float v1 = cast_to_float((enum ap_var_type)phdr.type);
        float v2;
        if (ginfo != nullptr) {
            v2 = get_default_value(this, *ginfo);
        } else {
            v2 = get_default_value(this, *info);
        }
        if (is_equal(v1,v2) && !force_save) {
            if (send_to_gcs) {
                GCS_SEND_PARAM(name, (enum ap_var_type)info->type, v2);
            }
            return;
        }
        if (!force_save &&
            (phdr.type != AP_PARAM_INT32 &&
             (fabsf(v1-v2) < 0.0001f*fabsf(v1)))) {
            // for other than 32 bit integers, we accept values within
            // 0.01 percent of the current value as being the same
            if (send_to_gcs) {
                GCS_SEND_PARAM(name, (enum ap_var_type)info->type, v2);
            }
            return;
        }
    }

    if (ofs+type_size((enum ap_var_type)phdr.type)+2*sizeof(phdr) >= _storage.size()) {
        // we are out of room for saving variables
        DEV_PRINTF("EEPROM full\n");
        return;
    }

    // write a new sentinal, then the data, then the header
    write_sentinal(ofs + sizeof(phdr) + type_size((enum ap_var_type)phdr.type));
    eeprom_write_check(ap, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
    eeprom_write_check(&phdr, ofs, sizeof(phdr));

    if (send_to_gcs) {
        send_parameter(name, (enum ap_var_type)phdr.type, idx);
    }
}

3.22 save

将变量通过队列保存。

void AP_Param::save(bool force_save)
{
    struct param_save p, p2;
    p.param = this;
    p.force_save = force_save;
    if (save_queue.peek(p2) &&
        p2.param == this &&
        p2.force_save == force_save) {
        // this one is already at the head of the list to be
        // saved. This check is cheap and catches the case where we
        // are flooding the save queue with one parameter (eg. mission
        // creation, changing MIS_TOTAL)
        return;
    }
    while (!save_queue.push(p)) {
        // if we can't save to the queue
        if (hal.util->get_soft_armed() && hal.scheduler->in_main_thread()) {
            // if we are armed in main thread then don't sleep, instead we lose the
            // parameter save
            return;
        }
        // when we are disarmed then loop waiting for a slot to become
        // available. This guarantees completion for large parameter
        // set loads
        hal.scheduler->expect_delay_ms(1);
        hal.scheduler->delay_microseconds(500);
        hal.scheduler->expect_delay_ms(0);
    }
}

3.23 flush

同步保存所有变量。

void AP_Param::flush(void)
{
    uint16_t counter = 200; // 2 seconds max
    while (counter-- && save_queue.available()) {
        hal.scheduler->expect_delay_ms(10);
        hal.scheduler->delay(10);
        hal.scheduler->expect_delay_ms(0);
    }
}

3.24 load

从EEPROM加载变量参数。

bool AP_Param::load(void)
{
    uint32_t group_element = 0;
    const struct GroupInfo *ginfo;
    struct GroupNesting group_nesting {};
    uint8_t idx;
    const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx);
    if (info == nullptr) {
        // we don't have any info on how to load it
        return false;
    }

    struct Param_header phdr;

    // create the header we will use to match the variable
    if (ginfo != nullptr) {
        phdr.type = ginfo->type;
    } else {
        phdr.type = info->type;
    }
    set_key(phdr, info->key);
    phdr.group_element = group_element;

    // scan EEPROM to find the right location
    uint16_t ofs;
    if (!scan(&phdr, &ofs)) {
        // if the value isn't stored in EEPROM then set the default value
        ptrdiff_t base;
        if (!get_base(*info, base)) {
            return false;
        }

        if (ginfo != nullptr) {
            // add in nested group offset
            ptrdiff_t group_offset = 0;
            for (uint8_t i=0; i<group_nesting.level; i++) {
                group_offset += group_nesting.group_ret[i]->offset;
            }
            set_value((enum ap_var_type)phdr.type, (void*)(base + ginfo->offset + group_offset),
                      get_default_value(this, *ginfo));
        } else {
            set_value((enum ap_var_type)phdr.type, (void*)base, 
                      get_default_value(this, *info));
        }
        return false;
    }

    if (phdr.type != AP_PARAM_VECTOR3F && idx != 0) {
        // only vector3f can have non-zero idx for now
        return false;
    }

    AP_Param *ap;
    ap = this;
    if (idx != 0) {
        ap = (AP_Param *)((ptrdiff_t)ap) - (idx*sizeof(float));
    }

    // found it
    _storage.read_block(ap, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
    return true;
}

3.25 load_all

最大可能加载变量参数。

bool AP_Param::load_all()
{
    struct Param_header phdr;
    uint16_t ofs = sizeof(AP_Param::EEPROM_header);

    reload_defaults_file(false);

    if (!registered_save_handler) {
        registered_save_handler = true;
        hal.scheduler->register_io_process(FUNCTOR_BIND((&save_dummy), &AP_Param::save_io_handler, void));
    }
    
    while (ofs < _storage.size()) {
        _storage.read_block(&phdr, ofs, sizeof(phdr));
        if (is_sentinal(phdr)) {
            // we've reached the sentinal
            sentinal_offset = ofs;
            return true;
        }

        const struct AP_Param::Info *info;
        void *ptr;

        info = find_by_header(phdr, &ptr);
        if (info != nullptr) {
            _storage.read_block(ptr, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
        }

        ofs += type_size((enum ap_var_type)phdr.type) + sizeof(phdr);
    }

    // we didn't find the sentinal
    Debug("no sentinal in load_all");
    return false;
}

3.26 reload_defaults_file

从hal.util默认文件或嵌入的param区域重新加载。

void AP_Param::reload_defaults_file(bool last_pass)
{
#if AP_PARAM_MAX_EMBEDDED_PARAM > 0
    if (param_defaults_data.length != 0) {
        load_embedded_param_defaults(last_pass);
        return;
    }
#endif

#if HAL_OS_POSIX_IO == 1
    /*
      if the HAL specifies a defaults parameter file then override
      defaults using that file
     */
    const char *default_file = hal.util->get_custom_defaults_file();
    if (default_file) {
        if (load_defaults_file(default_file, last_pass)) {
            printf("Loaded defaults from %s\n", default_file);
        } else {
            AP_HAL::panic("Failed to load defaults from %s\n", default_file);
        }
    }
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH)
    hal.util->set_cmdline_parameters();
#endif
}

3.27 load_object_from_eeprom

从EEPROM加载变特定量对象。

void AP_Param::load_object_from_eeprom(const void *object_pointer, const struct GroupInfo *group_info)
{
    struct Param_header phdr;
    uint16_t key;

    if (!find_key_by_pointer(object_pointer, key)) {
        DEV_PRINTF("ERROR: Unable to find param pointer\n");
        return;
    }
    
    for (uint8_t i=0; group_info[i].type != AP_PARAM_NONE; i++) {
        if (group_info[i].type == AP_PARAM_GROUP) {
            ptrdiff_t new_offset = 0;
            if (!adjust_group_offset(key, group_info[i], new_offset)) {
                continue;
            }
            const struct GroupInfo *ginfo = get_group_info(group_info[i]);
            if (ginfo != nullptr) {
                load_object_from_eeprom((void *)(((ptrdiff_t)object_pointer)+new_offset), ginfo);
            }
        }
        uint16_t ofs = sizeof(AP_Param::EEPROM_header);
        while (ofs < _storage.size()) {
            _storage.read_block(&phdr, ofs, sizeof(phdr));
            // note that this is an || not an && for robustness
            // against power off while adding a variable
            if (is_sentinal(phdr)) {
                // we've reached the sentinal
                sentinal_offset = ofs;
                break;
            }
            if (get_key(phdr) == key) {
                const struct AP_Param::Info *info;
                void *ptr;
                
                info = find_by_header(phdr, &ptr);
                if (info != nullptr) {
                    if ((ptrdiff_t)ptr == ((ptrdiff_t)object_pointer)+group_info[i].offset) {
                        _storage.read_block(ptr, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type));
                        break;
                    }
                }
            }
            ofs += type_size((enum ap_var_type)phdr.type) + sizeof(phdr);
        }
    }

    // reset cached param counter as we may be loading a dynamic var_info
    invalidate_count();
}

3.28 set_value

设置变量参数值。

void AP_Param::set_value(enum ap_var_type type, void *ptr, float value)
{
    switch (type) {
    case AP_PARAM_INT8:
        ((AP_Int8 *)ptr)->set(value);
        break;
    case AP_PARAM_INT16:
        ((AP_Int16 *)ptr)->set(value);
        break;
    case AP_PARAM_INT32:
        ((AP_Int32 *)ptr)->set(value);
        break;
    case AP_PARAM_FLOAT:
        ((AP_Float *)ptr)->set(value);
        break;
    default:
        break;
    }
}

3.29 set_float

设置变量float参数值。

void AP_Param::set_float(float value, enum ap_var_type var_type)
{
    if (isnan(value) || isinf(value)) {
        return;
    }

    // add a small amount before casting parameter values
    // from float to integer to avoid truncating to the
    // next lower integer value.
    float rounding_addition = 0.01f;
        
    // handle variables with standard type IDs
    if (var_type == AP_PARAM_FLOAT) {
        ((AP_Float *)this)->set(value);
    } else if (var_type == AP_PARAM_INT32) {
        if (value < 0) rounding_addition = -rounding_addition;
        float v = value+rounding_addition;
        v = constrain_float(v, INT32_MIN, INT32_MAX);
        ((AP_Int32 *)this)->set(v);
    } else if (var_type == AP_PARAM_INT16) {
        if (value < 0) rounding_addition = -rounding_addition;
        float v = value+rounding_addition;
        v = constrain_float(v, INT16_MIN, INT16_MAX);
        ((AP_Int16 *)this)->set(v);
    } else if (var_type == AP_PARAM_INT8) {
        if (value < 0) rounding_addition = -rounding_addition;
        float v = value+rounding_addition;
        v = constrain_float(v, INT8_MIN, INT8_MAX);
        ((AP_Int8 *)this)->set(v);
    }
}

3.30 setup_object_defaults

加载组中标量的默认值。

void AP_Param::setup_object_defaults(void const*, AP_Param::GroupInfo const*) {}

3.31 set_object_value

设置对象参数值。

bool AP_Param::set_object_value(const void *object_pointer,
                                const struct GroupInfo *group_info,
                                const char *name, float value)
{
    ptrdiff_t base = (ptrdiff_t)object_pointer;
    uint8_t type;
    bool found = false;
    for (uint8_t i=0;
         (type=group_info[i].type) != AP_PARAM_NONE;
         i++) {
        if (strcmp(name, group_info[i].name) == 0 && type <= AP_PARAM_FLOAT) {
            void *ptr = (void *)(base + group_info[i].offset);
            set_value((enum ap_var_type)type, ptr, value);
            // return true here ?
            found = true;
        }
    }
    return found;
}

3.32 setup_sketch_defaults

加载框架中所有标量的默认值。

void AP_Param::setup_sketch_defaults(void)
{
    setup();
    for (uint16_t i=0; i<_num_vars; i++) {
        const auto &info = var_info(i);
        uint8_t type = info.type;
        if (type <= AP_PARAM_FLOAT) {
            ptrdiff_t base;
            if (get_base(info, base)) {
                set_value((enum ap_var_type)type, (void*)base,
                          get_default_value((const AP_Param *)base, info));
            }
        }
    }
}

3.33 find_old_parameter

找到一个旧参数并返回。

bool AP_Param::find_old_parameter(const struct ConversionInfo *info, AP_Param *value)
{
    // find the old value in EEPROM.
    uint16_t pofs;
    AP_Param::Param_header header;
    header.type = info->type;
    set_key(header, info->old_key);
    header.group_element = info->old_group_element;
    if (!scan(&header, &pofs)) {
        // the old parameter isn't saved in the EEPROM.
        return false;
    }

    // load the old value from EEPROM
    _storage.read_block(value, pofs+sizeof(header), type_size((enum ap_var_type)header.type));
    return true;
}

3.34 convert_old_parameter

一个旧的参数转换为新的对象参数。

void AP_Param::convert_old_parameter(const struct ConversionInfo *info, float scaler, uint8_t flags)
{
    uint8_t old_value[type_size(info->type)];
    AP_Param *ap = (AP_Param *)&old_value[0];

    if (!find_old_parameter(info, ap)) {
        // the old parameter isn't saved in the EEPROM. It was
        // probably still set to the default value, which isn't stored
        // no need to convert
        return;
    }

    // find the new variable in the variable structures
    enum ap_var_type ptype;
    AP_Param *ap2;
    ap2 = find(&info->new_name[0], &ptype);
    if (ap2 == nullptr) {
        DEV_PRINTF("Unknown conversion '%s'\n", info->new_name);
        return;
    }

    // see if we can load it from EEPROM
    if (!(flags & CONVERT_FLAG_FORCE) && ap2->configured_in_storage()) {
        // the new parameter already has a value set by the user, or
        // has already been converted
        return;
    }

    // see if they are the same type and no scaling applied
    if (ptype == info->type && is_equal(scaler, 1.0f) && flags == 0) {
        // copy the value over only if the new parameter does not already
        // have the old value (via a default).
        if (memcmp(ap2, ap, sizeof(old_value)) != 0) {
            memcpy(ap2, ap, sizeof(old_value));
            // and save
            ap2->save();
        }
    } else if (ptype <= AP_PARAM_FLOAT && info->type <= AP_PARAM_FLOAT) {
        // perform scalar->scalar conversion
        float v = ap->cast_to_float(info->type);
        if (flags & CONVERT_FLAG_REVERSE) {
            // convert a _REV parameter to a _REVERSED parameter
            v = is_equal(v, -1.0f)?1:0;
        }
        if (!is_equal(v,ap2->cast_to_float(ptype))) {
            // the value needs to change
            set_value(ptype, ap2, v * scaler);
            ap2->save();
        }
    } else {
        // can't do vector<->scalar conversion, or different vector types
        DEV_PRINTF("Bad conversion type '%s'\n", info->new_name);
    }
}

3.35 convert_old_parameters

一个旧的参数列表转换为新的对象参数列表。

void AP_Param::convert_old_parameters(const struct ConversionInfo *conversion_table, uint8_t table_size, uint8_t flags)
{
    for (uint8_t i=0; i<table_size; i++) {
        convert_old_parameter(&conversion_table[i], 1.0f, flags);
    }
    // we need to flush here to prevent a later set_default_by_name()
    // causing a save to be done on a converted parameter
    flush();
}

3.36 convert_parameter_width

转换参数的宽度。

bool AP_Param::convert_parameter_width(ap_var_type old_ptype)
{
    if (configured_in_storage()) {
        // already converted or set by the user
        return false;
    }

    uint32_t group_element = 0;
    const struct GroupInfo *ginfo;
    struct GroupNesting group_nesting {};
    uint8_t idx;
    const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx);

    if (info == nullptr) {
        return false;
    }

    // remember the type
    ap_var_type new_ptype;
    if (ginfo != nullptr) {
        new_ptype = (ap_var_type)ginfo->type;
    } else {
        new_ptype = (ap_var_type)info->type;
    }
    
    // create the header we will use to scan for the variable
    struct Param_header phdr;
    phdr.type = old_ptype;
    set_key(phdr, info->key);
    phdr.group_element = group_element;

    // scan EEPROM to find the right location
    uint16_t pofs;
    if (!scan(&phdr, &pofs)) {
        // it isn't in storage
        return false;
    }

    // load the old value from EEPROM
    uint8_t old_value[type_size(old_ptype)];
    _storage.read_block(old_value, pofs+sizeof(phdr), sizeof(old_value));
    
    AP_Param *old_ap = (AP_Param *)&old_value[0];

    // going via float is safe as the only time we would be converting
    // from AP_Int32 is when converting to float
    float old_float_value = old_ap->cast_to_float(old_ptype);
    set_value(new_ptype, this, old_float_value);

    // force save as the new type
    save(true);

    return true;
}

3.37 convert_class

将类中的所有参数移动到新位置。

void AP_Param::convert_class(uint16_t param_key, void *object_pointer,
                                    const struct AP_Param::GroupInfo *group_info,
                                    uint16_t old_index, uint16_t old_top_element, bool is_top_level)
{
    const uint8_t group_shift = is_top_level ? 0 : 6;

    for (uint8_t i=0; group_info[i].type != AP_PARAM_NONE; i++) {
        struct ConversionInfo info;
        info.old_key = param_key;
        info.type = (ap_var_type)group_info[i].type;
        info.new_name = nullptr;

        uint16_t idx = group_info[i].idx;
        if (group_shift != 0 && idx == 0) {
            // Note: Index 0 is treated as 63 for group bit shifting purposes. See group_id()
            idx = 63;
        }

        info.old_group_element = (idx << group_shift) + old_index;

        uint8_t old_value[type_size(info.type)];
        AP_Param *ap = (AP_Param *)&old_value[0];
        
        if (!AP_Param::find_old_parameter(&info, ap)) {
            // the parameter wasn't set in the old eeprom
            continue;
        }

        AP_Param *ap2 = (AP_Param *)(group_info[i].offset + (uint8_t *)object_pointer);
        if (ap2->configured_in_storage()) {
            // user has already set a value, or previous conversion was done
            continue;
        }
        memcpy(ap2, ap, sizeof(old_value));
        // and save
        ap2->save();
    }

    // we need to flush here to prevent a later set_default_by_name()
    // causing a save to be done on a converted parameter
    flush();
}

3.38 get_param_by_index

通过组内的索引获取参数值。

bool AP_Param::get_param_by_index(void *obj_ptr, uint8_t idx, ap_var_type old_ptype, void *pvalue)
{
    uint16_t key;
    if (!find_top_level_key_by_pointer(obj_ptr, key)) {
        return false;
    }
    const ConversionInfo type_info = {key, idx, old_ptype, nullptr };
    return AP_Param::find_old_parameter(&type_info, (AP_Param *)pvalue);
}

3.39 erase_all

擦除所有EEPROM变量。

void AP_Param::erase_all(void)
{
    struct EEPROM_header hdr;

    // write the header
    hdr.magic[0] = k_EEPROM_magic0;
    hdr.magic[1] = k_EEPROM_magic1;
    hdr.revision = k_EEPROM_revision;
    hdr.spare    = 0;
    eeprom_write_check(&hdr, 0, sizeof(hdr));

    // add a sentinal directly after the header
    write_sentinal(sizeof(struct EEPROM_header));
}

3.40 first

获取第一个变量。

AP_Param *AP_Param::first(ParamToken *token, enum ap_var_type *ptype, float *default_val)
{
    token->key = 0;
    token->group_element = 0;
    token->idx = 0;
    if (_num_vars == 0) {
        return nullptr;
    }
    ptrdiff_t base;
    if (!get_base(var_info(0), base)) {
        // should be impossible, first var needs to be non-pointer
        return nullptr;
    }
    if (ptype != nullptr) {
        *ptype = (enum ap_var_type)var_info(0).type;
    }
#if AP_PARAM_DEFAULTS_ENABLED
    if (default_val != nullptr) {
        *default_val = get_default_value((AP_Param *)base, var_info(0));
    }
    check_default((AP_Param *)base, default_val);
#endif
    return (AP_Param *)base;
}

3.41 next

获取下一个变量。

static AP_Param *      next(ParamToken *token, enum ap_var_type *ptype) { return  next(token, ptype, false); }
AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype, bool skip_disabled, float *default_val)
{
    uint16_t i = token->key;
    bool found_current = false;
    if (i >= _num_vars) {
        // illegal token
        return nullptr;
    }
    enum ap_var_type type = (enum ap_var_type)var_info(i).type;

    // allow Vector3f to be seen as 3 variables. First as a vector,
    // then as 3 separate floats
    if (type == AP_PARAM_VECTOR3F && token->idx < 3) {
        token->idx++;
        if (ptype != nullptr) {
            *ptype = AP_PARAM_FLOAT;
        }
        AP_Param *ret = (AP_Param *)(((token->idx - 1u)*sizeof(float))+(ptrdiff_t)var_info(i).ptr);
#if AP_PARAM_DEFAULTS_ENABLED
        if (default_val != nullptr) {
            *default_val = get_default_value(ret, var_info(i));
        }
#endif
        return ret;
    }

    if (type != AP_PARAM_GROUP) {
        i++;
        found_current = true;
    }
    for (; i<_num_vars; i++) {
        const auto &info = var_info(i);
        if (!check_frame_type(info.flags)) {
            continue;
        }
        type = (enum ap_var_type)info.type;
        if (type == AP_PARAM_GROUP) {
            const struct GroupInfo *group_info = get_group_info(info);
            if (group_info == nullptr) {
                continue;
            }
            AP_Param *ap = next_group(i, group_info, &found_current, 0, 0, 0, token, ptype, skip_disabled, default_val);
            if (ap != nullptr) {
                return ap;
            }
        } else {
            // found the next one
            token->key = i;
            token->group_element = 0;
            token->idx = 0;
            if (ptype != nullptr) {
                *ptype = type;
            }
#if AP_PARAM_DEFAULTS_ENABLED
            if (default_val != nullptr) {
                *default_val = get_default_value((AP_Param *)info.ptr, info);
            }
#endif
            return (AP_Param *)(info.ptr);
        }
    }
    return nullptr;
}

3.42 next_scalar

获取下一个标量。

AP_Param *AP_Param::next_scalar(ParamToken *token, enum ap_var_type *ptype, float *default_val)
{
    AP_Param *ap;
    enum ap_var_type type;
    while ((ap = next(token, &type, true, default_val)) != nullptr && type > AP_PARAM_FLOAT) ;

    if (ap != nullptr) {
        if (ptype != nullptr) {
            *ptype = type;
        }
    }
#if AP_PARAM_DEFAULTS_ENABLED
    check_default(ap, default_val);
#endif
    return ap;
}

3.43 type_size

获取变量结构大小。

uint8_t AP_Param::type_size(enum ap_var_type type)
{
    switch (type) {
    case AP_PARAM_NONE:
    case AP_PARAM_GROUP:
        return 0;
    case AP_PARAM_INT8:
        return 1;
    case AP_PARAM_INT16:
        return 2;
    case AP_PARAM_INT32:
        return 4;
    case AP_PARAM_FLOAT:
        return 4;
    case AP_PARAM_VECTOR3F:
        return 3*4;
    }
    Debug("unknown type %d\n", type);
    return 0;
}

3.44 cast_to_float

将给定类型的变量强制转换为浮点。

float AP_Param::cast_to_float(enum ap_var_type type) const
{
    switch (type) {
    case AP_PARAM_INT8:
        return ((AP_Int8 *)this)->cast_to_float();
    case AP_PARAM_INT16:
        return ((AP_Int16 *)this)->cast_to_float();
    case AP_PARAM_INT32:
        return ((AP_Int32 *)this)->cast_to_float();
    case AP_PARAM_FLOAT:
        return ((AP_Float *)this)->cast_to_float();
    default:
        return NAN;
    }
}

3.45 check_var_info

验证_var_info[]表。

void AP_Param::check_var_info(void)
{
    uint16_t total_size = sizeof(struct EEPROM_header);

    for (uint16_t i=0; i<_num_vars; i++) {
        const auto &info = var_info(i);
        uint8_t type = info.type;
        uint16_t key = info.key;
        if (type == AP_PARAM_GROUP) {
            if (i == 0) {
                FATAL("first element can't be a group, for first() call");
            }
            const struct GroupInfo *group_info = get_group_info(info);
            if (group_info == nullptr) {
                continue;
            }
            check_group_info(group_info, &total_size, 0, strlen(info.name));
        } else {
            uint8_t size = type_size((enum ap_var_type)type);
            if (size == 0) {
                // not a valid type - the top level list can't contain
                // AP_PARAM_NONE
                FATAL("AP_PARAM_NONE at top level");
            }
            total_size += size + sizeof(struct Param_header);
        }
        if (duplicate_key(i, key)) {
            FATAL("duplicate key");
        }
        if (type != AP_PARAM_GROUP && (info.flags & AP_PARAM_FLAG_POINTER)) {
            FATAL("only groups can be pointers");
        }
    }

    // we no longer check if total_size is larger than _eeprom_size,
    // as we allow for more variables than could fit, relying on not
    // saving default values
}

3.46 configured

参数配置检查。

bool AP_Param::configured(void) const
{
    bool read_only;
    return configured_in_defaults_file(read_only) || configured_in_storage();
}

3.47 is_read_only

参数只读检查。

bool AP_Param::is_read_only(void) const
{
    if (num_read_only == 0) {
        return false;
    }
    bool read_only;
    if (configured_in_defaults_file(read_only)) {
        return read_only;
    }
    return false;
}

3.48 get_persistent_key

获取持久顶层密钥。

static uint16_t get_persistent_key(uint16_t key) { return var_info(key).key; }

3.49 count_parameters

树中参数数量。

uint16_t AP_Param::count_parameters(void)
{
    // if we haven't cached the parameter count yet...
    WITH_SEMAPHORE(_count_sem);
    if (_parameter_count != 0 &&
        _count_marker == _count_marker_done) {
        return _parameter_count;
    }
    /*
      cope with another thread invalidating the count while we are
      counting
     */
    uint8_t limit = 4;
    while ((_parameter_count == 0 ||
            _count_marker != _count_marker_done) &&
           limit--) {
        AP_Param  *vp;
        AP_Param::ParamToken token {};
        uint16_t count = 0;
        uint16_t marker = _count_marker;

        for (vp = AP_Param::first(&token, nullptr);
             vp != nullptr;
             vp = AP_Param::next_scalar(&token, nullptr)) {
            count++;
        }
        _parameter_count = count;
        _count_marker_done = marker;
    }
    return _parameter_count;
}

3.50 invalidate_count

无效标记计数。

void AP_Param::invalidate_count(void)
{
    // we don't take the semaphore here as we don't want to block. The
    // not-equal test is strong enough to ensure we get the right
    // answer
    _count_marker++;
}

3.51 set_hide_disabled_groups

注:不太理解这个函数的意义,设置隐藏去使能组???

static void set_hide_disabled_groups(bool value) { _hide_disabled_groups = value; }

3.52 set_frame_type_flags

设置frame type标记。

    static void set_frame_type_flags(uint16_t flags_to_set) {
        invalidate_count();
        _frame_type_flags |= flags_to_set;
    }

3.52 check_frame_type

检查frame type标记。

bool AP_Param::check_frame_type(uint16_t flags)
{
    if (flags & AP_PARAM_FLAG_HIDDEN) {
        // hidden on all frames
        return false;
    }
    uint16_t frame_flags = flags >> AP_PARAM_FRAME_TYPE_SHIFT;
    if (frame_flags == 0) {
        return true;
    }
    return (frame_flags & _frame_type_flags) != 0;
}

3.53 get_singleton

返回this指针。

static AP_Param *get_singleton() { return _singleton; }

3.54 load_defaults_file

从文件中获取默认变量集。

bool AP_Param::load_defaults_file(const char *filename, bool last_pass)
{
    if (filename == nullptr) {
        return false;
    }

    char *mutable_filename = strdup(filename);
    if (mutable_filename == nullptr) {
        AP_HAL::panic("AP_Param: Failed to allocate mutable string");
    }

    uint16_t num_defaults = 0;
    char *saveptr = nullptr;
    for (char *pname = strtok_r(mutable_filename, ",", &saveptr);
         pname != nullptr;
         pname = strtok_r(nullptr, ",", &saveptr)) {
        if (!count_defaults_in_file(pname, num_defaults)) {
            free(mutable_filename);
            return false;
        }
    }
    free(mutable_filename);

    delete[] param_overrides;
    num_param_overrides = 0;
    num_read_only = 0;

    param_overrides = new param_override[num_defaults];
    if (param_overrides == nullptr) {
        AP_HAL::panic("AP_Param: Failed to allocate overrides");
        return false;
    }

    if (num_defaults == 0) {
        return true;
    }

    saveptr = nullptr;
    mutable_filename = strdup(filename);
    if (mutable_filename == nullptr) {
        AP_HAL::panic("AP_Param: Failed to allocate mutable string");
    }
    for (char *pname = strtok_r(mutable_filename, ",", &saveptr);
         pname != nullptr;
         pname = strtok_r(nullptr, ",", &saveptr)) {
        if (!read_param_defaults_file(pname, last_pass)) {
            free(mutable_filename);
            return false;
        }
    }
    free(mutable_filename);

    num_param_overrides = num_defaults;

    return true;
}

3.55 add_default

在链表中新增一个变量。

void AP_Param::add_default(AP_Param *ap, float v)
{
    // Embedded defaults trump runtime, don't allow override
    for (uint16_t i=0; i<num_param_overrides; i++) {
        if (ap == param_overrides[i].object_ptr) {
            return;
        }
    }

    if (default_list != nullptr) {
        // check is param is already in list
        for (defaults_list *item = default_list; item; item = item->next) {
            // update existing entry
            if (item->ap == ap) {
                item->val = v;
                return;
            }
        }
    }

    // add to list
    defaults_list *new_item = new defaults_list;
    if (new_item == nullptr) {
        return;
    }
    new_item->ap = ap;
    new_item->val = v;
    new_item->next = default_list;
    default_list = new_item;
}

3.56 add_table

允许从脚本动态添加参数表。

bool AP_Param::add_table(uint8_t _key, const char *prefix, uint8_t num_params)
{
    // check if the key already exists. We only check base params to allow
    // for scripting reload without a conflict
    uint16_t key = uint16_t(_key) + AP_PARAM_DYNAMIC_KEY_BASE;
    for (uint16_t i=0; i<_num_vars_base; i++) {
        if (var_info(i).key == key) {
            return false;
        }
    }
    if (num_params > 63) {
        return false;
    }

    // we use a crc of the prefix to ensure the table key isn't re-used
    const int32_t crc = int32_t(crc32_small(0, (const uint8_t *)prefix, strlen(prefix)));
    int32_t current_crc;
    if (load_int32(key, 0, current_crc) && current_crc != crc) {
        // crc mismatch, we have a conflict with an existing use of this key
        return false;
    }

    // create the dynamic table if needed. This is never freed
    if (_var_info_dynamic == nullptr) {
        _var_info_dynamic = (Info *)calloc(AP_PARAM_MAX_DYNAMIC, sizeof(struct Info));
        if (_var_info_dynamic == nullptr) {
            return false;
        }
        for (uint8_t i=0; i<AP_PARAM_MAX_DYNAMIC; i++) {
            auto &info = _var_info_dynamic[i];
            info.type = AP_PARAM_NONE;
            info.name = _empty_string;
            info.key = 0xFFFF;
            info.ptr = nullptr;
            info.group_info = nullptr;
            info.flags = 0;
        }
        // make tables available
        _num_vars += AP_PARAM_MAX_DYNAMIC;
    }

    // find existing key (allows for script reload)
    uint8_t i;
    for (i=0; i<AP_PARAM_MAX_DYNAMIC; i++) {
        auto &info = _var_info_dynamic[i];
        if (info.type != AP_PARAM_NONE && info.key == key) {
            if (_dynamic_table_sizes[i] != 0 &&
                num_params > _dynamic_table_sizes[i]) {
                // can't expand the table at runtime
                return false;
            }
            if (strcmp(prefix, info.name) != 0) {
                // prefix has changed, reject as two scripts running
                // with the same key
                return false;
            }
            break;
        }
    }

    if (i == AP_PARAM_MAX_DYNAMIC) {
        // find an unused slot
        for (i=0; i<AP_PARAM_MAX_DYNAMIC; i++) {
            auto &info = _var_info_dynamic[i];
            if (info.type == AP_PARAM_NONE ) {
                break;
            }
        }
    }

    if (i == AP_PARAM_MAX_DYNAMIC) {
        // no empty slots
        return false;
    }

    auto &info = _var_info_dynamic[i];

    // create memory for the array of floats if needed
    // first float is used for the crc
    if (info.ptr == nullptr) {
        info.ptr = calloc(num_params+1, sizeof(float));
        if (info.ptr == nullptr) {
            return false;
        }
    }

    // allocate the name
    if (info.name == _empty_string) {
        info.name = strdup(prefix);
        if (info.name == nullptr) {
            free(const_cast<void*>(info.ptr));
            info.ptr = nullptr;
            info.name = _empty_string;
            return false;
        }
    }

    // if it doesn't exist then create the table
    if (info.group_info == nullptr) {
        info.group_info = (GroupInfo *)calloc(num_params+2, sizeof(GroupInfo));
        if (info.group_info == nullptr) {
            free(const_cast<void*>(info.ptr));
            free(const_cast<char*>(info.name));
            info.ptr = nullptr;
            info.name = _empty_string;
            return false;
        }
        // fill in footer for all entries
        for (uint8_t gi=1; gi<num_params+2; gi++) {
            auto &ginfo = const_cast<GroupInfo*>(info.group_info)[gi];
            ginfo.name = _empty_string;
            ginfo.idx = 0xff;
        }
        // hidden first parameter containing AP_Int32 crc
        auto &hinfo = const_cast<GroupInfo*>(info.group_info)[0];
        hinfo.flags = AP_PARAM_FLAG_HIDDEN;
        hinfo.name = _empty_string;
        hinfo.idx = 0;
        hinfo.offset = 0;
        hinfo.type = AP_PARAM_INT32;
        // fill in default value with the CRC. Relies on sizeof crc == sizeof float
        memcpy((uint8_t *)&hinfo.def_value, (const uint8_t *)&crc, sizeof(crc));
    }

    // remember the table size
    if (_dynamic_table_sizes[i] == 0) {
        _dynamic_table_sizes[i] = num_params;
    }
    
    // make the group active
    info.key = key;
    info.type = AP_PARAM_GROUP;

    invalidate_count();

    // save the CRC
    AP_Int32 *crc_param = const_cast<AP_Int32 *>((AP_Int32 *)info.ptr);
    crc_param->set(crc);
    crc_param->save(true);

    return true;
}

3.57 add_param

向动态表添加参数。

bool AP_Param::add_param(uint8_t _key, uint8_t param_num, const char *pname, float default_value)
{
    // check for valid values
    if (param_num == 0 || param_num > 63 || strlen(pname) > 16) {
        return false;
    }

    uint16_t key = uint16_t(_key) + AP_PARAM_DYNAMIC_KEY_BASE;
    // find the info
    uint8_t i;
    for (i=0; i<AP_PARAM_MAX_DYNAMIC; i++) {
        auto &info = _var_info_dynamic[i];
        if (info.key == key) {
            break;
        }
    }
    if (i == AP_PARAM_MAX_DYNAMIC) {
        // not found
        return false;
    }

    if (param_num > _dynamic_table_sizes[i]) {
        return false;
    }

    auto &info = _var_info_dynamic[i];
    if (info.ptr == nullptr) {
        return false;
    }

    // check CRC
    auto &hinfo = const_cast<GroupInfo*>(info.group_info)[0];
    const int32_t crc = *(const int32_t *)(&hinfo.def_value);

    int32_t current_crc;
    if (load_int32(key, 0, current_crc) && current_crc != crc) {
        // crc mismatch, we have a conflict with an existing use of this key
        return false;
    }

    // fill in idx of any gaps, leaving them hidden, this allows
    // scripts to remove parameters
    for (uint8_t j=1; j<param_num; j++) {
        auto &g = const_cast<GroupInfo*>(info.group_info)[j];
        if (g.idx == 0xff) {
            g.idx = j;
            g.flags = AP_PARAM_FLAG_HIDDEN;
            g.offset = j*sizeof(float);
            g.type = AP_PARAM_FLOAT;
        }
    }

    auto &ginfo = const_cast<GroupInfo*>(info.group_info)[param_num];

    if (ginfo.name == _empty_string) {
        // we don't allow name change while running
        ginfo.name = strdup(pname);
        if (ginfo.name == nullptr) {
            ginfo.name = _empty_string;
            return false;
        }
    }
    ginfo.offset = param_num*sizeof(float);
    ginfo.idx = param_num;
    float *def_value = const_cast<float *>(&ginfo.def_value);
    *def_value = default_value;
    ginfo.type = AP_PARAM_FLOAT;

    invalidate_count();

    // load from storage if available
    AP_Float *pvalues = const_cast<AP_Float *>((const AP_Float *)info.ptr);
    AP_Float &p = pvalues[param_num];
    p.set_default(default_value);
    p.load();

    return true;
}

3.58 load_int32

使用顶级键和组元素从EEPROM加载AP_INT32变量。

bool AP_Param::load_int32(uint16_t key, uint32_t group_element, int32_t &value)
{
    struct Param_header phdr;

    phdr.type = AP_PARAM_INT32;
    set_key(phdr, key);
    phdr.group_element = group_element;

    // scan EEPROM to find the right location
    uint16_t ofs;
    if (!scan(&phdr, &ofs)) {
        return false;
    }

    // found it
    _storage.read_block(&value, ofs+sizeof(phdr), type_size(AP_PARAM_INT32));
    return true;
}

3.59 storage_used

已使用存储空间。

static uint16_t storage_used() { return sentinal_offset; }

3.60 storage_size

存储空间大小。

static uint16_t storage_size() { return _storage.size(); }

4. 总结

对于Copter机型的参数表,详见:ArduCopter/Parameters.cpp

const AP_Param::Info Copter::var_info[] = {
    // @Param: FORMAT_VERSION
    // @DisplayName: Eeprom format version number
    // @Description: This value is incremented when changes are made to the eeprom format
    // @User: Advanced
    // @ReadOnly: True
    GSCALAR(format_version, "FORMAT_VERSION",   0),

    // @Param: SYSID_THISMAV
    // @DisplayName: MAVLink system ID of this vehicle
    // @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network
    // @Range: 1 255
    // @User: Advanced
    GSCALAR(sysid_this_mav, "SYSID_THISMAV",   MAV_SYSTEM_ID),

    // @Param: SYSID_MYGCS
    // @DisplayName: My ground station number
    // @Description: Allows restricting radio overrides to only come from my ground station
    // @Range: 1 255
    // @User: Advanced
    GSCALAR(sysid_my_gcs,   "SYSID_MYGCS",     255),

    // @Param: PILOT_THR_FILT
    // @DisplayName: Throttle filter cutoff
    // @Description: Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable
    // @User: Advanced
    // @Units: Hz
    // @Range: 0 10
    // @Increment: .5
    GSCALAR(throttle_filt,  "PILOT_THR_FILT",     0),

    // @Param: PILOT_TKOFF_ALT
    // @DisplayName: Pilot takeoff altitude
    // @Description: Altitude that altitude control modes will climb to when a takeoff is triggered with the throttle stick.
    // @User: Standard
    // @Units: cm
    // @Range: 0.0 1000.0
    // @Increment: 10
    GSCALAR(pilot_takeoff_alt,  "PILOT_TKOFF_ALT",  PILOT_TKOFF_ALT_DEFAULT),

    // @Param: PILOT_THR_BHV
    // @DisplayName: Throttle stick behavior
    // @Description: Bitmask containing various throttle stick options. TX with sprung throttle can set PILOT_THR_BHV to "1" so motor feedback when landed starts from mid-stick instead of bottom of stick.
    // @User: Standard
    // @Values: 0:None,1:Feedback from mid stick,2:High throttle cancels landing,4:Disarm on land detection
    // @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection
    GSCALAR(throttle_behavior, "PILOT_THR_BHV", 0),

    // @Group: SERIAL
    // @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
    GOBJECT(serial_manager, "SERIAL",   AP_SerialManager),

    // @Param: TELEM_DELAY
    // @DisplayName: Telemetry startup delay
    // @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
    // @User: Advanced
    // @Units: s
    // @Range: 0 30
    // @Increment: 1
    GSCALAR(telem_delay,            "TELEM_DELAY",     0),

    // @Param: GCS_PID_MASK
    // @DisplayName: GCS PID tuning mask
    // @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
    // @User: Advanced
    // @Values: 0:None,1:Roll,2:Pitch,4:Yaw,8:AccelZ
    // @Bitmask: 0:Roll,1:Pitch,2:Yaw,3:AccelZ
    GSCALAR(gcs_pid_mask,           "GCS_PID_MASK",     0),

#if MODE_RTL_ENABLED == ENABLED
    // @Param: RTL_ALT
    // @DisplayName: RTL Altitude
    // @Description: The minimum alt above home the vehicle will climb to before returning.  If the vehicle is flying higher than this value it will return at its current altitude.
    // @Units: cm
    // @Range: 200 300000
    // @Increment: 1
    // @User: Standard
    GSCALAR(rtl_altitude,   "RTL_ALT",     RTL_ALT),

    // @Param: RTL_CONE_SLOPE
    // @DisplayName: RTL cone slope
    // @Description: Defines a cone above home which determines maximum climb
    // @Range: 0.5 10.0
    // @Increment: .1
    // @Values: 0:Disabled,1:Shallow,3:Steep
    // @User: Standard
    GSCALAR(rtl_cone_slope,   "RTL_CONE_SLOPE",     RTL_CONE_SLOPE_DEFAULT),

    // @Param: RTL_SPEED
    // @DisplayName: RTL speed
    // @Description: Defines the speed in cm/s which the aircraft will attempt to maintain horizontally while flying home. If this is set to zero, WPNAV_SPEED will be used instead.
    // @Units: cm/s
    // @Range: 0 2000
    // @Increment: 50
    // @User: Standard
    GSCALAR(rtl_speed_cms,   "RTL_SPEED",     0),

    // @Param: RTL_ALT_FINAL
    // @DisplayName: RTL Final Altitude
    // @Description: This is the altitude the vehicle will move to as the final stage of Returning to Launch or after completing a mission.  Set to zero to land.
    // @Units: cm
    // @Range: 0 1000
    // @Increment: 1
    // @User: Standard
    GSCALAR(rtl_alt_final,  "RTL_ALT_FINAL", RTL_ALT_FINAL),

    // @Param: RTL_CLIMB_MIN
    // @DisplayName: RTL minimum climb
    // @Description: The vehicle will climb this many cm during the initial climb portion of the RTL
    // @Units: cm
    // @Range: 0 3000
    // @Increment: 10
    // @User: Standard
    GSCALAR(rtl_climb_min,  "RTL_CLIMB_MIN",    RTL_CLIMB_MIN_DEFAULT),

    // @Param: RTL_LOIT_TIME
    // @DisplayName: RTL loiter time
    // @Description: Time (in milliseconds) to loiter above home before beginning final descent
    // @Units: ms
    // @Range: 0 60000
    // @Increment: 1000
    // @User: Standard
    GSCALAR(rtl_loiter_time,      "RTL_LOIT_TIME",    RTL_LOITER_TIME),

    // @Param: RTL_ALT_TYPE
    // @DisplayName: RTL mode altitude type
    // @Description: RTL altitude type.  Set to 1 for Terrain following during RTL and then set WPNAV_RFND_USE=1 to use rangefinder or WPNAV_RFND_USE=0 to use Terrain database
    // @Values: 0:Relative to Home, 1:Terrain
    // @User: Standard
    GSCALAR(rtl_alt_type, "RTL_ALT_TYPE", 0),
#endif

    // @Param: FS_GCS_ENABLE
    // @DisplayName: Ground Station Failsafe Enable
    // @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled.
    // @Values: 0:Disabled/NoAction,1:RTL,2:RTL or Continue with Mission in Auto Mode (Removed in 4.0+-see FS_OPTIONS),3:SmartRTL or RTL,4:SmartRTL or Land,5:Land,6:Auto DO_LAND_START or RTL
    // @User: Standard
    GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISABLED),

    // @Param: GPS_HDOP_GOOD
    // @DisplayName: GPS Hdop Good
    // @Description: GPS Hdop value at or below this value represent a good position.  Used for pre-arm checks
    // @Range: 100 900
    // @User: Advanced
    GSCALAR(gps_hdop_good, "GPS_HDOP_GOOD", GPS_HDOP_GOOD_DEFAULT),

    // @Param: SUPER_SIMPLE
    // @DisplayName: Super Simple Mode
    // @Description: Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode. The bitmask is for flight mode switch positions
    // @Bitmask: 0:SwitchPos1, 1:SwitchPos2, 2:SwitchPos3, 3:SwitchPos4, 4:SwitchPos5, 5:SwitchPos6
    // @User: Standard
    GSCALAR(super_simple,   "SUPER_SIMPLE",     0),

    // @Param: WP_YAW_BEHAVIOR
    // @DisplayName: Yaw behaviour during missions
    // @Description: Determines how the autopilot controls the yaw during missions and RTL
    // @Values: 0:Never change yaw, 1:Face next waypoint, 2:Face next waypoint except RTL, 3:Face along GPS course
    // @User: Standard
    GSCALAR(wp_yaw_behavior,  "WP_YAW_BEHAVIOR",    WP_YAW_BEHAVIOR_DEFAULT),

    // @Param: LAND_SPEED
    // @DisplayName: Land speed
    // @Description: The descent speed for the final stage of landing in cm/s
    // @Units: cm/s
    // @Range: 30 200
    // @Increment: 10
    // @User: Standard
    GSCALAR(land_speed,             "LAND_SPEED",   LAND_SPEED),

    // @Param: LAND_SPEED_HIGH
    // @DisplayName: Land speed high
    // @Description: The descent speed for the first stage of landing in cm/s. If this is zero then WPNAV_SPEED_DN is used
    // @Units: cm/s
    // @Range: 0 500
    // @Increment: 10
    // @User: Standard
    GSCALAR(land_speed_high,        "LAND_SPEED_HIGH",   0),
    
    // @Param: PILOT_SPEED_UP
    // @DisplayName: Pilot maximum vertical speed ascending
    // @Description: The maximum vertical ascending velocity the pilot may request in cm/s
    // @Units: cm/s
    // @Range: 50 500
    // @Increment: 10
    // @User: Standard
    GSCALAR(pilot_speed_up,     "PILOT_SPEED_UP",   PILOT_VELZ_MAX),

    // @Param: PILOT_ACCEL_Z
    // @DisplayName: Pilot vertical acceleration
    // @Description: The vertical acceleration used when pilot is controlling the altitude
    // @Units: cm/s/s
    // @Range: 50 500
    // @Increment: 10
    // @User: Standard
    GSCALAR(pilot_accel_z,  "PILOT_ACCEL_Z",    PILOT_ACCEL_Z_DEFAULT),

    // @Param: FS_THR_ENABLE
    // @DisplayName: Throttle Failsafe Enable
    // @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
    // @Values:  0:Disabled,1:Enabled always RTL,2:Enabled Continue with Mission in Auto Mode (Removed in 4.0+),3:Enabled always Land,4:Enabled always SmartRTL or RTL,5:Enabled always SmartRTL or Land,6:Enabled Auto DO_LAND_START or RTL,7:Enabled always Brake or Land
    // @User: Standard
    GSCALAR(failsafe_throttle,  "FS_THR_ENABLE",   FS_THR_ENABLED_ALWAYS_RTL),

    // @Param: FS_THR_VALUE
    // @DisplayName: Throttle Failsafe Value
    // @Description: The PWM level in microseconds on channel 3 below which throttle failsafe triggers
    // @Range: 910 1100
    // @Units: PWM
    // @Increment: 1
    // @User: Standard
    GSCALAR(failsafe_throttle_value, "FS_THR_VALUE",      FS_THR_VALUE_DEFAULT),

    // @Param: THR_DZ
    // @DisplayName: Throttle deadzone
    // @Description: The deadzone above and below mid throttle in PWM microseconds. Used in AltHold, Loiter, PosHold flight modes
    // @User: Standard
    // @Range: 0 300
    // @Units: PWM
    // @Increment: 1
    GSCALAR(throttle_deadzone,  "THR_DZ",    THR_DZ_DEFAULT),

    // @Param: FLTMODE1
    // @DisplayName: Flight Mode 1
    // @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is <= 1230
    // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate,27:Auto RTL
    // @User: Standard
    GSCALAR(flight_mode1, "FLTMODE1",               (uint8_t)FLIGHT_MODE_1),

    // @Param: FLTMODE2
    // @CopyFieldsFrom: FLTMODE1
    // @DisplayName: Flight Mode 2
    // @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1230, <= 1360
    GSCALAR(flight_mode2, "FLTMODE2",               (uint8_t)FLIGHT_MODE_2),

    // @Param: FLTMODE3
    // @CopyFieldsFrom: FLTMODE1
    // @DisplayName: Flight Mode 3
    // @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1360, <= 1490
    GSCALAR(flight_mode3, "FLTMODE3",               (uint8_t)FLIGHT_MODE_3),

    // @Param: FLTMODE4
    // @CopyFieldsFrom: FLTMODE1
    // @DisplayName: Flight Mode 4
    // @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1490, <= 1620
    GSCALAR(flight_mode4, "FLTMODE4",               (uint8_t)FLIGHT_MODE_4),

    // @Param: FLTMODE5
    // @CopyFieldsFrom: FLTMODE1
    // @DisplayName: Flight Mode 5
    // @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1620, <= 1749
    GSCALAR(flight_mode5, "FLTMODE5",               (uint8_t)FLIGHT_MODE_5),

    // @Param: FLTMODE6
    // @CopyFieldsFrom: FLTMODE1
    // @DisplayName: Flight Mode 6
    // @Description: Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >=1750
    GSCALAR(flight_mode6, "FLTMODE6",               (uint8_t)FLIGHT_MODE_6),

    // @Param: FLTMODE_CH
    // @DisplayName: Flightmode channel
    // @Description: RC Channel to use for flight mode control
    // @Values: 0:Disabled,5:Channel5,6:Channel6,7:Channel7,8:Channel8,9:Channel9,10:Channel 10,11:Channel 11,12:Channel 12,13:Channel 13,14:Channel 14,15:Channel 15
    // @User: Advanced
    GSCALAR(flight_mode_chan, "FLTMODE_CH",         CH_MODE_DEFAULT),

    // @Param: INITIAL_MODE
    // @DisplayName: Initial flight mode
    // @Description: This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver.
    // @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,11:Drift,13:Sport,14:Flip,15:AutoTune,16:PosHold,17:Brake,18:Throw,19:Avoid_ADSB,20:Guided_NoGPS,21:Smart_RTL,22:FlowHold,23:Follow,24:ZigZag,25:SystemID,26:Heli_Autorotate
    // @User: Advanced
    GSCALAR(initial_mode,        "INITIAL_MODE",     (uint8_t)Mode::Number::STABILIZE),

    // @Param: SIMPLE
    // @DisplayName: Simple mode bitmask
    // @Description: Bitmask which holds which flight modes use simple heading mode (eg bit 0 = 1 means Flight Mode 0 uses simple mode). The bitmask is for flightmode switch positions.
    // @Bitmask: 0:SwitchPos1, 1:SwitchPos2, 2:SwitchPos3, 3:SwitchPos4, 4:SwitchPos5, 5:SwitchPos6
    // @User: Advanced
    GSCALAR(simple_modes, "SIMPLE",                 0),

    // @Param: LOG_BITMASK
    // @DisplayName: Log bitmask
    // @Description: Bitmap of what on-board log types to enable. This value is made up of the sum of each of the log types you want to be saved. It is usually best just to enable all basiclog types by setting this to 65535. 
    // @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Control Tuning,5:Navigation Tuning,6:RC input,7:IMU,8:Mission Commands,9:Battery Monitor,10:RC output,11:Optical Flow,12:PID,13:Compass,15:Camera,17:Motors,18:Fast IMU,19:Raw IMU,20:Video Stabilization,21:Fast harmonic notch logging
    // @User: Standard
    GSCALAR(log_bitmask,    "LOG_BITMASK",          DEFAULT_LOG_BITMASK),

    // @Param: ESC_CALIBRATION
    // @DisplayName: ESC Calibration
    // @Description: Controls whether ArduCopter will enter ESC calibration on the next restart.  Do not adjust this parameter manually.
    // @User: Advanced
    // @Values: 0:Normal Start-up, 1:Start-up in ESC Calibration mode if throttle high, 2:Start-up in ESC Calibration mode regardless of throttle, 3:Start-up and automatically calibrate ESCs, 9:Disabled
    GSCALAR(esc_calibrate, "ESC_CALIBRATION",       0),

    // @Param: TUNE
    // @DisplayName: Channel 6 Tuning
    // @Description: Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob
    // @User: Standard
    // @Values: 0:None,1:Stab Roll/Pitch kP,4:Rate Roll/Pitch kP,5:Rate Roll/Pitch kI,21:Rate Roll/Pitch kD,3:Stab Yaw kP,6:Rate Yaw kP,26:Rate Yaw kD,56:Rate Yaw Filter,55:Motor Yaw Headroom,14:AltHold kP,7:Throttle Rate kP,34:Throttle Accel kP,35:Throttle Accel kI,36:Throttle Accel kD,12:Loiter Pos kP,22:Velocity XY kP,28:Velocity XY kI,10:WP Speed,25:Acro Roll/Pitch deg/s,40:Acro Yaw deg/s,45:RC Feel,13:Heli Ext Gyro,38:Declination,39:Circle Rate,46:Rate Pitch kP,47:Rate Pitch kI,48:Rate Pitch kD,49:Rate Roll kP,50:Rate Roll kI,51:Rate Roll kD,52:Rate Pitch FF,53:Rate Roll FF,54:Rate Yaw FF,58:SysID Magnitude,59:PSC Angle Max
    GSCALAR(radio_tuning, "TUNE",                   0),

    // @Param: FRAME_TYPE
    // @DisplayName: Frame Type (+, X, V, etc)
    // @Description: Controls motor mixing for multicopters.  Not used for Tri or Traditional Helicopters.
    // @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 5:A-Tail, 10:Y6B, 11:Y6F, 12:BetaFlightX, 13:DJIX, 14:ClockwiseX, 15: I, 18: BetaFlightXReversed, 19:Y4
    // @User: Standard
    // @RebootRequired: True
    GSCALAR(frame_type, "FRAME_TYPE", HAL_FRAME_TYPE_DEFAULT),

    // @Group: ARMING_
    // @Path: ../libraries/AP_Arming/AP_Arming.cpp
    GOBJECT(arming,                 "ARMING_", AP_Arming_Copter),

    // @Param: DISARM_DELAY
    // @DisplayName: Disarm delay
    // @Description: Delay before automatic disarm in seconds after landing touchdown detection. A value of zero disables auto disarm. If Emergency Motor stop active, delay time is half this value.
    // @Units: s
    // @Range: 0 127
    // @User: Advanced
    GSCALAR(disarm_delay, "DISARM_DELAY",           AUTO_DISARMING_DELAY),
    
    // @Param: ANGLE_MAX
    // @DisplayName: Angle Max
    // @Description: Maximum lean angle in all flight modes
    // @Units: cdeg
    // @Increment: 10
    // @Range: 1000 8000
    // @User: Advanced
    ASCALAR(angle_max, "ANGLE_MAX",                 DEFAULT_ANGLE_MAX),

#if MODE_POSHOLD_ENABLED == ENABLED
    // @Param: PHLD_BRAKE_RATE
    // @DisplayName: PosHold braking rate
    // @Description: PosHold flight mode's rotation rate during braking in deg/sec
    // @Units: deg/s
    // @Range: 4 12
    // @User: Advanced
    GSCALAR(poshold_brake_rate, "PHLD_BRAKE_RATE",  POSHOLD_BRAKE_RATE_DEFAULT),

    // @Param: PHLD_BRAKE_ANGLE
    // @DisplayName: PosHold braking angle max
    // @Description: PosHold flight mode's max lean angle during braking in centi-degrees
    // @Units: cdeg
    // @Increment: 10
    // @Range: 2000 4500
    // @User: Advanced
    GSCALAR(poshold_brake_angle_max, "PHLD_BRAKE_ANGLE",  POSHOLD_BRAKE_ANGLE_DEFAULT),
#endif

    // @Param: LAND_REPOSITION
    // @DisplayName: Land repositioning
    // @Description: Enables user input during LAND mode, the landing phase of RTL, and auto mode landings.
    // @Values: 0:No repositioning, 1:Repositioning
    // @User: Advanced
    GSCALAR(land_repositioning, "LAND_REPOSITION",     LAND_REPOSITION_DEFAULT),

    // @Param: FS_EKF_ACTION
    // @DisplayName: EKF Failsafe Action
    // @Description: Controls the action that will be taken when an EKF failsafe is invoked
    // @Values: 1:Land, 2:AltHold, 3:Land even in Stabilize
    // @User: Advanced
    GSCALAR(fs_ekf_action, "FS_EKF_ACTION",    FS_EKF_ACTION_DEFAULT),

    // @Param: FS_EKF_THRESH
    // @DisplayName: EKF failsafe variance threshold
    // @Description: Allows setting the maximum acceptable compass, velocity, position and height variances. Used in arming check and EKF failsafe.
    // @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed
    // @User: Advanced
    GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH",    FS_EKF_THRESHOLD_DEFAULT),

    // @Param: FS_CRASH_CHECK
    // @DisplayName: Crash check enable
    // @Description: This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.
    // @Values: 0:Disabled, 1:Enabled
    // @User: Advanced
    GSCALAR(fs_crash_check, "FS_CRASH_CHECK",    1),

    // @Param: RC_SPEED
    // @DisplayName: ESC Update Speed
    // @Description: This is the speed in Hertz that your ESCs will receive updates
    // @Units: Hz
    // @Range: 50 490
    // @Increment: 1
    // @User: Advanced
    GSCALAR(rc_speed, "RC_SPEED",              RC_FAST_SPEED),

#if MODE_ACRO_ENABLED == ENABLED || MODE_SPORT_ENABLED == ENABLED
    // @Param: ACRO_BAL_ROLL
    // @DisplayName: Acro Balance Roll
    // @Description: rate at which roll angle returns to level in acro and sport mode.  A higher value causes the vehicle to return to level faster. For helicopter sets the decay rate of the virtual flybar in the roll axis. A higher value causes faster decay of desired to actual attitude.
    // @Range: 0 3
    // @Increment: 0.1
    // @User: Advanced
    GSCALAR(acro_balance_roll,      "ACRO_BAL_ROLL",    ACRO_BALANCE_ROLL),

    // @Param: ACRO_BAL_PITCH
    // @DisplayName: Acro Balance Pitch
    // @Description: rate at which pitch angle returns to level in acro and sport mode.  A higher value causes the vehicle to return to level faster. For helicopter sets the decay rate of the virtual flybar in the pitch axis. A higher value causes faster decay of desired to actual attitude.
    // @Range: 0 3
    // @Increment: 0.1
    // @User: Advanced
    GSCALAR(acro_balance_pitch,     "ACRO_BAL_PITCH",   ACRO_BALANCE_PITCH),
#endif

    // ACRO_RP_EXPO moved to Command Model class

#if MODE_ACRO_ENABLED == ENABLED
    // @Param: ACRO_TRAINER
    // @DisplayName: Acro Trainer
    // @Description: Type of trainer used in acro mode
    // @Values: 0:Disabled,1:Leveling,2:Leveling and Limited
    // @User: Advanced
    GSCALAR(acro_trainer,   "ACRO_TRAINER",     (uint8_t)ModeAcro::Trainer::LIMITED),
#endif

    // variables not in the g class which contain EEPROM saved variables

#if AP_CAMERA_ENABLED
    // @Group: CAM
    // @Path: ../libraries/AP_Camera/AP_Camera.cpp
    GOBJECT(camera, "CAM", AP_Camera),
#endif

    // @Group: RELAY_
    // @Path: ../libraries/AP_Relay/AP_Relay.cpp
    GOBJECT(relay,                  "RELAY_", AP_Relay),

#if PARACHUTE == ENABLED
    // @Group: CHUTE_
    // @Path: ../libraries/AP_Parachute/AP_Parachute.cpp
    GOBJECT(parachute, "CHUTE_", AP_Parachute),
#endif

#if AP_LANDINGGEAR_ENABLED
    // @Group: LGR_
    // @Path: ../libraries/AP_LandingGear/AP_LandingGear.cpp
    GOBJECT(landinggear,    "LGR_", AP_LandingGear),
#endif

#if FRAME_CONFIG == HELI_FRAME
    // @Group: IM_
    // @Path: ../libraries/AC_InputManager/AC_InputManager_Heli.cpp
    GOBJECT(input_manager, "IM_", AC_InputManager_Heli),
#endif

    // @Group: COMPASS_
    // @Path: ../libraries/AP_Compass/AP_Compass.cpp
    GOBJECT(compass,        "COMPASS_", Compass),

    // @Group: INS
    // @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
    GOBJECT(ins,            "INS", AP_InertialSensor),

    // @Group: WPNAV_
    // @Path: ../libraries/AC_WPNav/AC_WPNav.cpp
    GOBJECTPTR(wp_nav, "WPNAV_",       AC_WPNav),

    // @Group: LOIT_
    // @Path: ../libraries/AC_WPNav/AC_Loiter.cpp
    GOBJECTPTR(loiter_nav, "LOIT_", AC_Loiter),

#if MODE_CIRCLE_ENABLED == ENABLED
    // @Group: CIRCLE_
    // @Path: ../libraries/AC_WPNav/AC_Circle.cpp
    GOBJECTPTR(circle_nav, "CIRCLE_",  AC_Circle),
#endif

    // @Group: ATC_
    // @Path: ../libraries/AC_AttitudeControl/AC_AttitudeControl.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp,../libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
#if FRAME_CONFIG == HELI_FRAME
    GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Heli),
#else
    GOBJECTPTR(attitude_control, "ATC_", AC_AttitudeControl_Multi),
#endif

    // @Group: PSC
    // @Path: ../libraries/AC_AttitudeControl/AC_PosControl.cpp
    GOBJECTPTR(pos_control, "PSC", AC_PosControl),

    // @Group: SR0_
    // @Path: GCS_Mavlink.cpp
    GOBJECTN(_gcs.chan_parameters[0],  gcs0,       "SR0_",     GCS_MAVLINK_Parameters),

#if MAVLINK_COMM_NUM_BUFFERS >= 2
    // @Group: SR1_
    // @Path: GCS_Mavlink.cpp
    GOBJECTN(_gcs.chan_parameters[1],  gcs1,       "SR1_",     GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 3
    // @Group: SR2_
    // @Path: GCS_Mavlink.cpp
    GOBJECTN(_gcs.chan_parameters[2],  gcs2,       "SR2_",     GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 4
    // @Group: SR3_
    // @Path: GCS_Mavlink.cpp
    GOBJECTN(_gcs.chan_parameters[3],  gcs3,       "SR3_",     GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 5
    // @Group: SR4_
    // @Path: GCS_Mavlink.cpp
    GOBJECTN(_gcs.chan_parameters[4],  gcs4,       "SR4_",     GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 6
    // @Group: SR5_
    // @Path: GCS_Mavlink.cpp
    GOBJECTN(_gcs.chan_parameters[5],  gcs5,       "SR5_",     GCS_MAVLINK_Parameters),
#endif

#if MAVLINK_COMM_NUM_BUFFERS >= 7
    // @Group: SR6_
    // @Path: GCS_Mavlink.cpp
    GOBJECTN(_gcs.chan_parameters[6],  gcs6,       "SR6_",     GCS_MAVLINK_Parameters),
#endif

    // @Group: AHRS_
    // @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
    GOBJECT(ahrs,                   "AHRS_",    AP_AHRS),

#if HAL_MOUNT_ENABLED
    // @Group: MNT
    // @Path: ../libraries/AP_Mount/AP_Mount.cpp
    GOBJECT(camera_mount,           "MNT",  AP_Mount),
#endif

    // @Group: LOG
    // @Path: ../libraries/AP_Logger/AP_Logger.cpp
    GOBJECT(logger,           "LOG",  AP_Logger),

    // @Group: BATT
    // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
    GOBJECT(battery,                "BATT",         AP_BattMonitor),

    // @Group: BRD_
    // @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
    GOBJECT(BoardConfig,            "BRD_",       AP_BoardConfig),

#if HAL_MAX_CAN_PROTOCOL_DRIVERS
    // @Group: CAN_
    // @Path: ../libraries/AP_CANManager/AP_CANManager.cpp
    GOBJECT(can_mgr,        "CAN_",       AP_CANManager),
#endif

#if HAL_SPRAYER_ENABLED
    // @Group: SPRAY_
    // @Path: ../libraries/AC_Sprayer/AC_Sprayer.cpp
    GOBJECT(sprayer,                "SPRAY_",       AC_Sprayer),
#endif

#if AP_SIM_ENABLED
    // @Group: SIM_
    // @Path: ../libraries/SITL/SITL.cpp
    GOBJECT(sitl, "SIM_", SITL::SIM),
#endif

    // @Group: BARO
    // @Path: ../libraries/AP_Baro/AP_Baro.cpp
    GOBJECT(barometer, "BARO", AP_Baro),

    // GPS driver
    // @Group: GPS
    // @Path: ../libraries/AP_GPS/AP_GPS.cpp
    GOBJECT(gps, "GPS", AP_GPS),

    // @Group: SCHED_
    // @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
    GOBJECT(scheduler, "SCHED_", AP_Scheduler),

    // @Group: AVOID_
    // @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp
#if AC_AVOID_ENABLED == ENABLED
    GOBJECT(avoid,      "AVOID_",   AC_Avoid),
#endif

#if HAL_RALLY_ENABLED
    // @Group: RALLY_
    // @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp
    GOBJECT(rally,      "RALLY_",   AP_Rally_Copter),
#endif

#if FRAME_CONFIG == HELI_FRAME
    // @Group: H_
    // @Path: ../libraries/AP_Motors/AP_MotorsHeli_Single.cpp,../libraries/AP_Motors/AP_MotorsHeli_Dual.cpp,../libraries/AP_Motors/AP_MotorsHeli.cpp
    GOBJECTVARPTR(motors, "H_",        &copter.motors_var_info),
#else
    // @Group: MOT_
    // @Path: ../libraries/AP_Motors/AP_MotorsMulticopter.cpp
    GOBJECTVARPTR(motors, "MOT_",      &copter.motors_var_info),
#endif

    // @Group: RCMAP_
    // @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
    GOBJECT(rcmap, "RCMAP_",        RCMapper),

#if HAL_NAVEKF2_AVAILABLE
    // @Group: EK2_
    // @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
    GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),
#endif

#if HAL_NAVEKF3_AVAILABLE
    // @Group: EK3_
    // @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
    GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
#endif

#if MODE_AUTO_ENABLED == ENABLED
    // @Group: MIS_
    // @Path: ../libraries/AP_Mission/AP_Mission.cpp
    GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission),
#endif

    // @Group: RSSI_
    // @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
    GOBJECT(rssi, "RSSI_",  AP_RSSI),
    
#if RANGEFINDER_ENABLED == ENABLED
    // @Group: RNGFND
    // @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
    GOBJECT(rangefinder,   "RNGFND", RangeFinder),
#endif

#if AP_TERRAIN_AVAILABLE
    // @Group: TERRAIN_
    // @Path: ../libraries/AP_Terrain/AP_Terrain.cpp
    GOBJECT(terrain,                "TERRAIN_", AP_Terrain),
#endif

#if AP_OPTICALFLOW_ENABLED
    // @Group: FLOW
    // @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp
    GOBJECT(optflow,   "FLOW", AP_OpticalFlow),
#endif

#if PRECISION_LANDING == ENABLED
    // @Group: PLND_
    // @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
    GOBJECT(precland, "PLND_", AC_PrecLand),
#endif

#if AP_RPM_ENABLED
    // @Group: RPM
    // @Path: ../libraries/AP_RPM/AP_RPM.cpp
    GOBJECT(rpm_sensor, "RPM", AP_RPM),
#endif

#if HAL_ADSB_ENABLED
    // @Group: ADSB_
    // @Path: ../libraries/AP_ADSB/AP_ADSB.cpp
    GOBJECT(adsb,                "ADSB_", AP_ADSB),

    // @Group: AVD_
    // @Path: ../libraries/AP_Avoidance/AP_Avoidance.cpp
    GOBJECT(avoidance_adsb, "AVD_", AP_Avoidance_Copter),
#endif

    // @Group: NTF_
    // @Path: ../libraries/AP_Notify/AP_Notify.cpp
    GOBJECT(notify, "NTF_",  AP_Notify),

#if MODE_THROW_ENABLED == ENABLED
    // @Param: THROW_MOT_START
    // @DisplayName: Start motors before throwing is detected
    // @Description: Used by Throw mode. Controls whether motors will run at the speed set by MOT_SPIN_MIN or will be stopped when armed and waiting for the throw.
    // @Values: 0:Stopped,1:Running
    // @User: Standard
    GSCALAR(throw_motor_start, "THROW_MOT_START", (float)ModeThrow::PreThrowMotorState::STOPPED),
#endif

#if OSD_ENABLED || OSD_PARAM_ENABLED
    // @Group: OSD
    // @Path: ../libraries/AP_OSD/AP_OSD.cpp
    GOBJECT(osd, "OSD", AP_OSD),
#endif

#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED
    // @Group: CC
    // @Path: ../libraries/AC_CustomControl/AC_CustomControl.cpp
    GOBJECT(custom_control, "CC", AC_CustomControl),
#endif

    // @Group:
    // @Path: Parameters.cpp
    GOBJECT(g2, "",  ParametersG2),

    // @Group:
    // @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
    PARAM_VEHICLE_INFO,

    AP_VAREND
}

每一行定义变量的宏定义如下:

// Vehicle defines for info struct
#define GSCALAR(v, name, def)                { name, &AP_PARAM_VEHICLE_NAME.g.v,                   {def_value : def},                   0,                                                  Parameters::k_param_ ## v,          AP_PARAM_VEHICLE_NAME.g.v.vtype }
#define GARRAY(v, index, name, def)          { name, &AP_PARAM_VEHICLE_NAME.g.v[index],            {def_value : def},                   0,                                                  Parameters::k_param_ ## v ## index, AP_PARAM_VEHICLE_NAME.g.v[index].vtype }
#define ASCALAR(v, name, def)                { name, (const void *)&AP_PARAM_VEHICLE_NAME.aparm.v, {def_value : def},                   0,                                                  Parameters::k_param_ ## v,          AP_PARAM_VEHICLE_NAME.aparm.v.vtype }
#define GGROUP(v, name, class)               { name, &AP_PARAM_VEHICLE_NAME.g.v,                   {group_info : class::var_info},      0,                                                  Parameters::k_param_ ## v,          AP_PARAM_GROUP }
#define GOBJECT(v, name, class)              { name, (const void *)&AP_PARAM_VEHICLE_NAME.v,       {group_info : class::var_info},      0,                                                  Parameters::k_param_ ## v,          AP_PARAM_GROUP }
#define GOBJECTPTR(v, name, class)           { name, (const void *)&AP_PARAM_VEHICLE_NAME.v,       {group_info : class::var_info},      AP_PARAM_FLAG_POINTER,                              Parameters::k_param_ ## v,          AP_PARAM_GROUP }
#define GOBJECTVARPTR(v, name, var_info_ptr) { name, (const void *)&AP_PARAM_VEHICLE_NAME.v,       {group_info_ptr : var_info_ptr},     AP_PARAM_FLAG_POINTER | AP_PARAM_FLAG_INFO_POINTER, Parameters::k_param_ ## v,          AP_PARAM_GROUP }
#define GOBJECTN(v, pname, name, class)      { name, (const void *)&AP_PARAM_VEHICLE_NAME.v,       {group_info : class::var_info},      0,                                                  Parameters::k_param_ ## pname,      AP_PARAM_GROUP }
#define PARAM_VEHICLE_INFO                   { "",   (const void *)&AP_PARAM_VEHICLE_NAME,         {group_info : AP_Vehicle::var_info}, 0,                                                  Parameters::k_param_vehicle,        AP_PARAM_GROUP }
#define AP_VAREND                            { "",   nullptr,                                      {group_info : nullptr },             0,                                                  0,                                  AP_PARAM_NONE }

关于具体变量的含义和应用,这块需要结合实际应用。

注:目前ArduPilot关于参数的文档有点过时,Adding a New Parameter to Copter,如果阅读请以代码为准。

5. 参考资料

【1】ArduPilot开源飞控系统之简单介绍
【2】ArduPilot之开源代码框架

猜你喜欢

转载自blog.csdn.net/lida2003/article/details/130813316
今日推荐