Custom parameters not saved

Hi all,

I have added new parameters to the Ardusub/Parameters.cpp class.
The parameters show up in QGC and can be set without an issue.
However, after a reboot the parameters are always back at default value.

Interestingly enough, i also added a parameter to AP_MOTOR/Motors6dof.cpp class, which also works fine. This parameter is also persisten through reboots.

Example of implementation in Ardusub/Parameters.cpp

  • added to var_info
	// @Param: DOCKING_YAW_P
	// @DisplayName: Docking Mode Heading P
	// @Description: Docking mode heading PID controller, P gain
	// @Range:-10000 10000
	// @User: Advanced
	GSCALAR(docking_mode_yaw_p, "DOCKING_YAW_P", DOCKING_YAW_P_DEFAULT),

The example parameter is added in the enum in Ardusub/Parameters.h as

k_param_docking_mode_yaw_p = 5000,

and the variable is defined as

AP_Float docking_mode_yaw_p;

The default value is defined in ArduSub/config.h as

#ifndef DOCKING_YAW_P_DEFAULT
#define DOCKING_YAW_P_DEFAULT 25
#endif

Any thoughts on how to get this to be persisten through reboots?

Cheers

Hi @lars148, welcome to the forum :slight_smile:

Custom ArduSub parameters isn’t something I’ve needed to work with yet, so I’ve asked our software team what’s required to make them persistent, and will get back to you :slight_smile:

1 Like

Thanks for the replye @EliotBR .

Changing the enum value in Ardusub/Parameters.h from 5000 to 240 seems to be the trick

k_param_docking_mode_yaw_p = 240

Perhaps there is a restriction on how many parameters can be stored?
And an enum value above this restricts it from being saved?
Haven’t seen any references to this in the source code, but looking forward to hear what the dev team has to say.

1 Like

Given the values need to be stored in EEPROM to be persistent, it’s possible there just isn’t enough space for 5000 parameters. You could do a binary search to try to find the cross-over number if you want, although my suspicion would be some power of 2 (either 512, 1024, 2048, or 4096).

I think the answer is in AP_Param.h:

AP_Param::Param_header describes how keys (e.g., k_param_foo) is stored in the eeprom. There are 9 bits allocated, which means the maximum number of keys is 512.

The size of each parameter varies from 1 byte (INT8) to 12 bytes (VECTOR3F), so you might hit the storage limit before you hit the max # of keys.