AP_Param: enable reduced size support for AP_Periph

This commit is contained in:
Andrew Tridgell 2019-05-27 11:32:42 +10:00
parent 88fbbfba09
commit f897eae89d
2 changed files with 22 additions and 6 deletions

View File

@ -44,6 +44,12 @@ extern const AP_HAL::HAL &hal;
# define Debug(fmt, args ...)
#endif
#ifdef HAL_NO_GCS
#define GCS_SEND_PARAM(name, type, v)
#else
#define GCS_SEND_PARAM(name, type, v) gcs().send_parameter_value(name, type, v)
#endif
// Note about AP_Vector3f handling.
// The code has special cases for AP_Vector3f to allow it to be viewed
// as both a single 3 element vector and as a set of 3 AP_Float
@ -75,6 +81,7 @@ bool AP_Param::registered_save_handler;
// we need a dummy object for the parameter save callback
static AP_Param save_dummy;
#if AP_PARAM_MAX_EMBEDDED_PARAM > 0
/*
this holds default parameters in the normal NAME=value form for a
parameter file. It can be manipulated by apj_tool.py to change the
@ -86,6 +93,7 @@ const AP_Param::param_defaults_struct AP_Param::param_defaults_data = {
AP_PARAM_MAX_EMBEDDED_PARAM,
0
};
#endif
// storage object
StorageAccess AP_Param::_storage(StorageManager::StorageParam);
@ -1054,7 +1062,7 @@ void AP_Param::save_sync(bool force_save)
v2 = get_default_value(this, &info->def_value);
}
if (is_equal(v1,v2) && !force_save) {
gcs().send_parameter_value(name, (enum ap_var_type)info->type, v2);
GCS_SEND_PARAM(name, (enum ap_var_type)info->type, v2);
return;
}
if (!force_save &&
@ -1062,7 +1070,7 @@ void AP_Param::save_sync(bool force_save)
(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
gcs().send_parameter_value(name, (enum ap_var_type)info->type, v2);
GCS_SEND_PARAM(name, (enum ap_var_type)info->type, v2);
return;
}
}
@ -1371,10 +1379,12 @@ bool AP_Param::load_all()
*/
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
/*
@ -1982,6 +1992,7 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass)
#endif // HAL_OS_POSIX_IO
#if AP_PARAM_MAX_EMBEDDED_PARAM > 0
/*
count the number of embedded parameter defaults
*/
@ -2106,6 +2117,7 @@ void AP_Param::load_embedded_param_defaults(bool last_pass)
}
num_param_overrides = num_defaults;
}
#endif // AP_PARAM_MAX_EMBEDDED_PARAM > 0
/*
find a default value given a pointer to a default value in flash
@ -2132,7 +2144,7 @@ void AP_Param::send_parameter(const char *name, enum ap_var_type var_type, uint8
}
if (var_type != AP_PARAM_VECTOR3F) {
// nice and simple for scalar types
gcs().send_parameter_value(name, var_type, cast_to_float(var_type));
GCS_SEND_PARAM(name, var_type, cast_to_float(var_type));
return;
}
@ -2140,6 +2152,7 @@ void AP_Param::send_parameter(const char *name, enum ap_var_type var_type, uint8
// of a set of the first element of a AP_Vector3f. This happens as the ap->save() call can't
// distinguish between a vector and scalar save. It means that setting first element of a vector
// via MAVLink results in sending all 3 elements to the GCS
#ifndef HAL_NO_GCS
const Vector3f &v = ((AP_Vector3f *)this)->get();
char name2[AP_MAX_NAME_SIZE+1];
strncpy(name2, name, AP_MAX_NAME_SIZE);
@ -2147,11 +2160,12 @@ void AP_Param::send_parameter(const char *name, enum ap_var_type var_type, uint8
char &name_axis = name2[strlen(name)-1];
name_axis = 'X';
gcs().send_parameter_value(name2, AP_PARAM_FLOAT, v.x);
GCS_SEND_PARAM(name2, AP_PARAM_FLOAT, v.x);
name_axis = 'Y';
gcs().send_parameter_value(name2, AP_PARAM_FLOAT, v.y);
GCS_SEND_PARAM(name2, AP_PARAM_FLOAT, v.y);
name_axis = 'Z';
gcs().send_parameter_value(name2, AP_PARAM_FLOAT, v.z);
GCS_SEND_PARAM(name2, AP_PARAM_FLOAT, v.z);
#endif // HAL_NO_GCS
}
/*

View File

@ -503,6 +503,7 @@ private:
/*
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];
@ -511,6 +512,7 @@ private:
volatile char data[AP_PARAM_MAX_EMBEDDED_PARAM];
};
static const param_defaults_struct param_defaults_data;
#endif
static bool check_group_info(const struct GroupInfo *group_info, uint16_t *total_size,