Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Allow for read-only parameters using @READONLY marker #12076

Merged
merged 2 commits into from
Sep 12, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
65 changes: 57 additions & 8 deletions libraries/AP_Param/AP_Param.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,7 @@ const AP_Param::Info *AP_Param::_var_info;

struct AP_Param::param_override *AP_Param::param_overrides = nullptr;
uint16_t AP_Param::num_param_overrides = 0;
uint16_t AP_Param::num_read_only = 0;

ObjectBuffer<AP_Param::param_save> AP_Param::save_queue{30};
bool AP_Param::registered_save_handler;
Expand Down Expand Up @@ -1243,8 +1244,11 @@ bool AP_Param::configured_in_storage(void) const
return scan(&phdr, &ofs) && (phdr.type == AP_PARAM_VECTOR3F || idx == 0);
}

bool AP_Param::configured_in_defaults_file(void) const
bool AP_Param::configured_in_defaults_file(bool &read_only) const
{
if (num_param_overrides == 0) {
return false;
}
uint32_t group_element = 0;
const struct GroupInfo *ginfo;
struct GroupNesting group_nesting {};
Expand All @@ -1257,13 +1261,32 @@ bool AP_Param::configured_in_defaults_file(void) const

for (uint16_t i=0; i<num_param_overrides; i++) {
if (this == param_overrides[i].object_ptr) {
read_only = param_overrides[i].read_only;
return true;
}
}

return false;
}

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

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;
}

// set a AP_Param variable to a specified value
void AP_Param::set_value(enum ap_var_type type, void *ptr, float value)
{
Expand Down Expand Up @@ -1849,25 +1872,37 @@ void AP_Param::set_float(float value, enum ap_var_type var_type)
/*
parse a parameter file line
*/
bool AP_Param::parse_param_line(char *line, char **vname, float &value)
bool AP_Param::parse_param_line(char *line, char **vname, float &value, bool &read_only)
{
if (line[0] == '#') {
return false;
}
char *saveptr = nullptr;
char *pname = strtok_r(line, ", =\t", &saveptr);
/*
note that we need the \r\n as delimiters to prevent us getting
strings with line termination in the results
*/
char *pname = strtok_r(line, ", =\t\r\n", &saveptr);
tridge marked this conversation as resolved.
Show resolved Hide resolved
if (pname == nullptr) {
return false;
}
if (strlen(pname) > AP_MAX_NAME_SIZE) {
return false;
}
const char *value_s = strtok_r(nullptr, ", =\t", &saveptr);
const char *value_s = strtok_r(nullptr, ", =\t\r\n", &saveptr);
if (value_s == nullptr) {
return false;
}
value = atof(value_s);
*vname = pname;

const char *flags_s = strtok_r(nullptr, ", =\t\r\n", &saveptr);
if (flags_s && strcmp(flags_s, "@READONLY") == 0) {
read_only = true;
} else {
read_only = false;
}

return true;
}

Expand All @@ -1890,7 +1925,8 @@ bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaul
while (fgets(line, sizeof(line)-1, f)) {
char *pname;
float value;
if (!parse_param_line(line, &pname, value)) {
bool read_only;
if (!parse_param_line(line, &pname, value, read_only)) {
continue;
}
enum ap_var_type var_type;
Expand Down Expand Up @@ -1918,7 +1954,8 @@ bool AP_Param::read_param_defaults_file(const char *filename, bool last_pass)
while (fgets(line, sizeof(line)-1, f)) {
char *pname;
float value;
if (!parse_param_line(line, &pname, value)) {
bool read_only;
if (!parse_param_line(line, &pname, value, read_only)) {
continue;
}
enum ap_var_type var_type;
Expand All @@ -1935,6 +1972,10 @@ bool AP_Param::read_param_defaults_file(const char *filename, bool last_pass)
}
param_overrides[idx].object_ptr = vp;
param_overrides[idx].value = value;
param_overrides[idx].read_only = read_only;
if (read_only) {
num_read_only++;
}
idx++;
if (!vp->configured_in_storage()) {
vp->set_float(value, var_type);
Expand Down Expand Up @@ -1972,6 +2013,7 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass)

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

param_overrides = new param_override[num_defaults];
if (param_overrides == nullptr) {
Expand Down Expand Up @@ -2019,6 +2061,7 @@ bool AP_Param::count_embedded_param_defaults(uint16_t &count)
char line[100];
char *pname;
float value;
bool read_only;
uint16_t i;
uint16_t n = MIN(length, sizeof(line)-1);
for (i=0;i<n;i++) {
Expand All @@ -2041,7 +2084,7 @@ bool AP_Param::count_embedded_param_defaults(uint16_t &count)
continue;
}

if (!parse_param_line(line, &pname, value)) {
if (!parse_param_line(line, &pname, value, read_only)) {
continue;
}

Expand All @@ -2065,6 +2108,7 @@ void AP_Param::load_embedded_param_defaults(bool last_pass)
delete[] param_overrides;
param_overrides = nullptr;
num_param_overrides = 0;
num_read_only = 0;

uint16_t num_defaults = 0;
if (!count_embedded_param_defaults(num_defaults)) {
Expand All @@ -2085,6 +2129,7 @@ void AP_Param::load_embedded_param_defaults(bool last_pass)
char line[100];
char *pname;
float value;
bool read_only;
uint16_t i;
uint16_t n = MIN(length, sizeof(line)-1);
for (i=0;i<n;i++) {
Expand All @@ -2106,7 +2151,7 @@ void AP_Param::load_embedded_param_defaults(bool last_pass)
continue;
}

if (!parse_param_line(line, &pname, value)) {
if (!parse_param_line(line, &pname, value, read_only)) {
continue;
}
enum ap_var_type var_type;
Expand All @@ -2123,6 +2168,10 @@ void AP_Param::load_embedded_param_defaults(bool last_pass)
}
param_overrides[idx].object_ptr = vp;
param_overrides[idx].value = value;
param_overrides[idx].read_only = read_only;
if (read_only) {
num_read_only++;
}
idx++;
if (!vp->configured_in_storage()) {
vp->set_float(value, var_type);
Expand Down
11 changes: 8 additions & 3 deletions libraries/AP_Param/AP_Param.h
Original file line number Diff line number Diff line change
Expand Up @@ -426,14 +426,17 @@ class AP_Param
static bool check_var_info(void);

// return true if the parameter is configured in the defaults file
bool configured_in_defaults_file(void) const;
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;

// return true if the parameter is configured
bool configured(void) const { return configured_in_defaults_file() || configured_in_storage(); }
bool configured(void) const;

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

// count of parameters in tree
static uint16_t count_parameters(void);

Expand Down Expand Up @@ -601,7 +604,7 @@ class AP_Param
// find a default value given a pointer to a default value in flash
static float get_default_value(const AP_Param *object_ptr, const float *def_value_ptr);

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

#if HAL_OS_POSIX_IO == 1
/*
Expand Down Expand Up @@ -632,9 +635,11 @@ class AP_Param
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;
Expand Down
2 changes: 1 addition & 1 deletion libraries/GCS_MAVLink/GCS_Param.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -276,7 +276,7 @@ void GCS_MAVLINK::handle_param_set(const mavlink_message_t &msg)

float old_value = vp->cast_to_float(var_type);

if (parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) {
if ((parameter_flags & AP_PARAM_FLAG_INTERNAL_USE_ONLY) || vp->is_read_only()) {
gcs().send_text(MAV_SEVERITY_WARNING, "Param write denied (%s)", key);
// echo back the incorrect value so that we fulfull the
// parameter state machine requirements:
Expand Down