Skip to content

Commit

Permalink
AP_Param: move complex AP_ParamT functions to cpp
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and tridge committed Sep 12, 2022
1 parent 5ad860a commit 3d98122
Show file tree
Hide file tree
Showing 2 changed files with 147 additions and 70 deletions.
80 changes: 10 additions & 70 deletions libraries/AP_Param/AP_Param.h
Original file line number Diff line number Diff line change
Expand Up @@ -820,70 +820,30 @@ class AP_ParamT : public AP_Param
}

// set a parameter that is an ENABLE param
void set_enable(const T &v) {
if (v != _value) {
invalidate_count();
}
_value = v;
}
void set_enable(const T &v);

/// Sets if the parameter is unconfigured
///
void set_default(const T &v) {
#if AP_PARAM_DEFAULTS_ENABLED
add_default(this, (float)v);
#endif
if (!configured()) {
set(v);
}
}
void set_default(const T &v);

/// Sets parameter and default
///
void set_and_default(const T &v) {
#if AP_PARAM_DEFAULTS_ENABLED
add_default(this, (float)v);
#endif
set(v);
}
void set_and_default(const T &v);

/// Value setter - set value, tell GCS
///
void set_and_notify(const T &v) {
// We do want to compare each value, even floats, since it being the same here
// is the result of previously setting it.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wfloat-equal"
if (v != _value) {
#pragma GCC diagnostic pop
set(v);
notify();
}
}
void set_and_notify(const T &v);

/// Combined set and save
///
void set_and_save(const T &v) {
bool force = fabsf((float)(_value - v)) < FLT_EPSILON;
set(v);
save(force);
}
void set_and_save(const T &v);

/// Combined set and save, but only does the save if the value if
/// different from the current ram value, thus saving us a
/// scan(). This should only be used where we have not set() the
/// value separately, as otherwise the value in EEPROM won't be
/// updated correctly.
void set_and_save_ifchanged(const T &v) {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wfloat-equal"
if (v == _value) {
#pragma GCC diagnostic pop
return;
}
set(v);
save(true);
}
void set_and_save_ifchanged(const T &v);

/// Conversion to T returns a reference to the value.
///
Expand All @@ -895,9 +855,7 @@ class AP_ParamT : public AP_Param

/// AP_ParamT types can implement AP_Param::cast_to_float
///
float cast_to_float(void) const {
return (float)_value;
}
float cast_to_float(void) const;

protected:
T _value;
Expand Down Expand Up @@ -933,36 +891,18 @@ class AP_ParamV : public AP_Param

/// Value setter - set value, tell GCS
///
void set_and_notify(const T &v) {
if (v != _value) {
set(v);
notify();
}
}
void set_and_notify(const T &v);

/// Combined set and save
///
void set_and_save(const T &v) {
bool force = (_value != v);
set(v);
save(force);
}
void set_and_save(const T &v);

/// Combined set and save, but only does the save if the value is
/// different from the current ram value, thus saving us a
/// scan(). This should only be used where we have not set() the
/// value separately, as otherwise the value in EEPROM won't be
/// updated correctly.
void set_and_save_ifchanged(const T &v) {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wfloat-equal"
if (_value == v) {
#pragma GCC diagnostic pop
return;
}
set(v);
save(true);
}
void set_and_save_ifchanged(const T &v);


/// Conversion to T returns a reference to the value.
Expand Down
137 changes: 137 additions & 0 deletions libraries/AP_Param/AP_ParamT.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,137 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/

#include "AP_Param.h"
#include <AP_Math/AP_Math.h>

// Param type template functions

// set a parameter that is an ENABLE param
template<typename T, ap_var_type PT>
void AP_ParamT<T, PT>::set_enable(const T &v) {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wfloat-equal"
if (v != _value) {
#pragma GCC diagnostic pop
invalidate_count();
}
_value = v;
}

// Sets if the parameter is unconfigured
template<typename T, ap_var_type PT>
void AP_ParamT<T, PT>::set_default(const T &v) {
#if AP_PARAM_DEFAULTS_ENABLED
add_default(this, (float)v);
#endif
if (!configured()) {
set(v);
}
}

// Sets parameter and default
template<typename T, ap_var_type PT>
void AP_ParamT<T, PT>::set_and_default(const T &v) {
#if AP_PARAM_DEFAULTS_ENABLED
add_default(this, (float)v);
#endif
set(v);
}

// Value setter - set value, tell GCS
template<typename T, ap_var_type PT>
void AP_ParamT<T, PT>::set_and_notify(const T &v) {
// We do want to compare each value, even floats, since it being the same here
// is the result of previously setting it.
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wfloat-equal"
if (v != _value) {
#pragma GCC diagnostic pop
set(v);
notify();
}
}

// Combined set and save
template<typename T, ap_var_type PT>
void AP_ParamT<T, PT>::set_and_save(const T &v) {
bool force = fabsf((float)(_value - v)) < FLT_EPSILON;
set(v);
save(force);
}

// Combined set and save, but only does the save if the value if
// different from the current ram value, thus saving us a
// scan(). This should only be used where we have not set() the
// value separately, as otherwise the value in EEPROM won't be
// updated correctly.
template<typename T, ap_var_type PT>
void AP_ParamT<T, PT>::set_and_save_ifchanged(const T &v) {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wfloat-equal"
if (v == _value) {
#pragma GCC diagnostic pop
return;
}
set(v);
save(true);
}

// AP_ParamT types can implement AP_Param::cast_to_float
template<typename T, ap_var_type PT>
float AP_ParamT<T, PT>::cast_to_float(void) const {
return (float)_value;
}

template class AP_ParamT<float, AP_PARAM_FLOAT>;
template class AP_ParamT<int8_t, AP_PARAM_INT8>;
template class AP_ParamT<int16_t, AP_PARAM_INT16>;
template class AP_ParamT<int32_t, AP_PARAM_INT32>;

// Value setter - set value, tell GCS
template<typename T, ap_var_type PT>
void AP_ParamV<T, PT>::set_and_notify(const T &v) {
if (v != _value) {
set(v);
notify();
}
}

/// Combined set and save
template<typename T, ap_var_type PT>
void AP_ParamV<T, PT>::set_and_save(const T &v) {
bool force = (_value != v);
set(v);
save(force);
}

// Combined set and save, but only does the save if the value is
// different from the current ram value, thus saving us a
// scan(). This should only be used where we have not set() the
// value separately, as otherwise the value in EEPROM won't be
// updated correctly.
template<typename T, ap_var_type PT>
void AP_ParamV<T, PT>::set_and_save_ifchanged(const T &v) {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wfloat-equal"
if (_value == v) {
#pragma GCC diagnostic pop
return;
}
set(v);
save(true);
}

template class AP_ParamV<Vector3f, AP_PARAM_VECTOR3F>;

0 comments on commit 3d98122

Please sign in to comment.