Compare commits

...

1 Commits

Author SHA1 Message Date
Daniel Agar b6157c89a0 parameters: eliminate param_reset(param_t param) from public C API 2022-12-19 16:50:09 -05:00
11 changed files with 36 additions and 137 deletions
@@ -146,12 +146,6 @@ public:
void set(float val) { _val = val; }
void reset()
{
param_reset_no_notification(handle());
update();
}
bool update() { return param_get(handle(), &_val) == 0; }
param_t handle() const { return param_handle(p); }
@@ -198,12 +192,6 @@ public:
void set(float val) { _val = val; }
void reset()
{
param_reset_no_notification(handle());
update();
}
bool update() { return param_get(handle(), &_val) == 0; }
param_t handle() const { return param_handle(p); }
@@ -248,12 +236,6 @@ public:
void set(int32_t val) { _val = val; }
void reset()
{
param_reset_no_notification(handle());
update();
}
bool update() { return param_get(handle(), &_val) == 0; }
param_t handle() const { return param_handle(p); }
@@ -300,12 +282,6 @@ public:
void set(int32_t val) { _val = val; }
void reset()
{
param_reset_no_notification(handle());
update();
}
bool update() { return param_get(handle(), &_val) == 0; }
param_t handle() const { return param_handle(p); }
@@ -358,12 +334,6 @@ public:
void set(bool val) { _val = val; }
void reset()
{
param_reset_no_notification(handle());
update();
}
bool update()
{
int32_t value_int;
@@ -143,12 +143,6 @@ public:
void set(float val) { _val = val; }
void reset()
{
//param_reset_no_notification(handle()); // TODO
update();
}
bool update()
{
return true; // TODO
@@ -207,12 +201,6 @@ public:
void set(float val) { _val = val; }
void reset()
{
//param_reset_no_notification(handle());
update();
}
bool update()
{
return true;
@@ -269,12 +257,6 @@ public:
void set(int32_t val) { _val = val; }
void reset()
{
//param_reset_no_notification(handle());
update();
}
bool update()
{
//return param_get(handle(), &_val) == 0;
@@ -333,12 +315,6 @@ public:
void set(int32_t val) { _val = val; }
void reset()
{
//param_reset_no_notification(handle());
update();
}
bool update()
{
//return param_get(handle(), &_val) == 0;
@@ -397,12 +373,6 @@ public:
void set(bool val) { _val = val; }
void reset()
{
//param_reset_no_notification(handle());
update();
}
bool update()
{
int32_t value_int;
-16
View File
@@ -273,22 +273,6 @@ __EXPORT int param_set_no_notification(param_t param, const void *val);
*/
__EXPORT void param_notify_changes(void);
/**
* Reset a parameter to its default value.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @return Zero on success, nonzero on failure
*/
__EXPORT int param_reset(param_t param);
/**
* Reset a parameter to its default value, but do not notify the system about the change.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @return Zero on success, nonzero on failure
*/
__EXPORT int param_reset_no_notification(param_t param);
/**
* Reset all parameters to their default values.
*/
+4 -7
View File
@@ -914,7 +914,7 @@ int param_set_default_value(param_t param, const void *val)
return result;
}
static int param_reset_internal(param_t param, bool notify = true)
static int param_reset_internal(param_t param)
{
param_wbuf_s *s = nullptr;
bool param_found = false;
@@ -941,16 +941,13 @@ static int param_reset_internal(param_t param, bool notify = true)
param_unlock_writer();
if (s != nullptr && notify) {
if (s != nullptr) {
param_notify_changes();
}
return (!param_found);
}
int param_reset(param_t param) { return param_reset_internal(param, true); }
int param_reset_no_notification(param_t param) { return param_reset_internal(param, false); }
static void
param_reset_all_internal(bool auto_save)
{
@@ -1000,7 +997,7 @@ param_reset_excludes(const char *excludes[], int num_excludes)
}
if (!exclude) {
param_reset(param);
param_reset_internal(param);
}
}
}
@@ -1025,7 +1022,7 @@ param_reset_specific(const char *resets[], int num_resets)
}
if (reset) {
param_reset(param);
param_reset_internal(param);
}
}
}
-12
View File
@@ -139,18 +139,6 @@ int param_ioctl(unsigned int cmd, unsigned long arg)
}
break;
case PARAMIOCRESET: {
paramiocreset_t *data = (paramiocreset_t *)arg;
if (data->notification) {
data->ret = param_reset(data->param);
} else {
data->ret = param_reset_no_notification(data->param);
}
}
break;
case PARAMIOCRESETGROUP: {
paramiocresetgroup_t *data = (paramiocresetgroup_t *)arg;
-7
View File
@@ -118,13 +118,6 @@ typedef struct paramiocsetdefault {
int ret;
} paramiocsetdefault_t;
#define PARAMIOCRESET _PARAMIOC(13)
typedef struct paramiocreset {
const param_t param;
const bool notification;
int ret;
} paramiocreset_t;
#define PARAMIOCRESETGROUP _PARAMIOC(14)
typedef enum {
PARAM_RESET_ALL,
-14
View File
@@ -152,20 +152,6 @@ int param_set_default_value(param_t param, const void *val)
return data.ret;
}
int param_reset(param_t param)
{
paramiocreset_t data = {param, true, PX4_ERROR};
boardctl(PARAMIOCRESET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_reset_no_notification(param_t param)
{
paramiocreset_t data = {param, false, PX4_ERROR};
boardctl(PARAMIOCRESET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
void
param_reset_all()
{
+12 -6
View File
@@ -162,42 +162,48 @@ void RCUpdate::parameters_updated()
if (param_get(param_find("RC_MAP_MODE_SW"), &rc_map_value) == PX4_OK) {
if (rc_map_value != 0) {
PX4_WARN("RC_MAP_MODE_SW deprecated");
param_reset(param_find("RC_MAP_MODE_SW"));
rc_map_value = 0;
param_set(param_find("RC_MAP_MODE_SW"), &rc_map_value);
}
}
if (param_get(param_find("RC_MAP_RATT_SW"), &rc_map_value) == PX4_OK) {
if (rc_map_value != 0) {
PX4_WARN("RC_MAP_RATT_SW deprecated");
param_reset(param_find("RC_MAP_RATT_SW"));
rc_map_value = 0;
param_set(param_find("RC_MAP_RATT_SW"), &rc_map_value);
}
}
if (param_get(param_find("RC_MAP_POSCTL_SW"), &rc_map_value) == PX4_OK) {
if (rc_map_value != 0) {
PX4_WARN("RC_MAP_POSCTL_SW deprecated");
param_reset(param_find("RC_MAP_POSCTL_SW"));
rc_map_value = 0;
param_set(param_find("RC_MAP_POSCTL_SW"), &rc_map_value);
}
}
if (param_get(param_find("RC_MAP_ACRO_SW"), &rc_map_value) == PX4_OK) {
if (rc_map_value != 0) {
PX4_WARN("RC_MAP_ACRO_SW deprecated");
param_reset(param_find("RC_MAP_ACRO_SW"));
rc_map_value = 0;
param_set(param_find("RC_MAP_ACRO_SW"), &rc_map_value);
}
}
if (param_get(param_find("RC_MAP_STAB_SW"), &rc_map_value) == PX4_OK) {
if (rc_map_value != 0) {
PX4_WARN("RC_MAP_STAB_SW deprecated");
param_reset(param_find("RC_MAP_STAB_SW"));
rc_map_value = 0;
param_set(param_find("RC_MAP_STAB_SW"), &rc_map_value);
}
}
if (param_get(param_find("RC_MAP_MAN_SW"), &rc_map_value) == PX4_OK) {
if (rc_map_value != 0) {
PX4_WARN("RC_MAP_MAN_SW deprecated");
param_reset(param_find("RC_MAP_MAN_SW"));
rc_map_value = 0;
param_set(param_find("RC_MAP_MAN_SW"), &rc_map_value);
}
}
}
@@ -382,7 +382,8 @@ void VehicleAngularVelocity::ParametersUpdate(bool force)
// IMU_GYRO_RATEMAX
if (_param_imu_gyro_ratemax.get() <= 0) {
const int32_t imu_gyro_ratemax = _param_imu_gyro_ratemax.get();
_param_imu_gyro_ratemax.reset();
_param_imu_gyro_ratemax.set(400);
_param_imu_gyro_ratemax.commit();
PX4_WARN("IMU_GYRO_RATEMAX invalid (%" PRId32 "), resetting to default %" PRId32 ")", imu_gyro_ratemax,
_param_imu_gyro_ratemax.get());
}
+4 -1
View File
@@ -57,7 +57,10 @@ test_param(int argc, char *argv[])
return 1;
}
if (param_reset(p) != OK) {
// default value 12345678
int32_t test_params_default_value = 12345678;
if (param_set(p, &test_params_default_value) != OK) {
warnx("failed param reset");
return 1;
}
+14 -13
View File
@@ -226,11 +226,17 @@ bool ParameterTest::ResetAllExcludesWildcard()
bool ParameterTest::CustomDefaults()
{
int32_t value = 0;
// reset to default
const int32_t test_1_default_value = 2;
int32_t value = test_1_default_value;
param_t param_test_1 = param_find("TEST_1");
param_reset(param_test_1);
param_set(param_test_1, &value);
param_set_default_value(param_test_1, &value);
// TEST_1 default value 2
value = 0;
param_get(param_test_1, &value);
ut_compare("value for param doesn't match default value", value, 2); // TEST_1 default value 2
ut_compare("value for param doesn't match default value", value, test_1_default_value);
// verify underlying default value
int32_t default_value = 0;
@@ -247,10 +253,11 @@ bool ParameterTest::CustomDefaults()
param_get_default_value(param_test_1, &default_value);
ut_compare("value for param default doesn't match custom default value", default_value, 123456789);
// verify new value
value = 0;
param_get(param_test_1, &value);
ut_compare("param value not custom default", value, 123456789);
// // verify new value
// TODO: arguably once the parameter is set to default value initially it should "track" the new default value
// value = 0;
// param_get(param_test_1, &value);
// ut_compare("param value not custom default", value, 123456789);
// set to new value and verify
value = 987654321;
@@ -259,12 +266,6 @@ bool ParameterTest::CustomDefaults()
param_get(param_test_1, &value);
ut_compare("param value not saved", value, 987654321);
// reset (to custom default)
param_reset(param_test_1);
value = 0;
param_get(param_test_1, &value);
ut_compare("param value not reset to custom default", value, 123456789);
return true;
}