Browse Source

AP_NavEKF: fixed use of configured() vs configured_in_storage()

apm_2208
Andrew Tridgell 3 years ago committed by Peter Barker
parent
commit
72470e290c
  1. 12
      libraries/AP_NavEKF/AP_NavEKF_Source.cpp
  2. 8
      libraries/AP_NavEKF/AP_NavEKF_Source.h

12
libraries/AP_NavEKF/AP_NavEKF_Source.cpp

@ -286,20 +286,20 @@ bool AP_NavEKF_Source::usingGPS() const @@ -286,20 +286,20 @@ bool AP_NavEKF_Source::usingGPS() const
}
// true if some parameters have been configured (used during parameter conversion)
bool AP_NavEKF_Source::configured_in_storage()
bool AP_NavEKF_Source::configured()
{
if (config_in_storage) {
if (_configured) {
return true;
}
// first source parameter is used to determine if configured or not
config_in_storage = _source_set[0].posxy.configured_in_storage();
_configured = _source_set[0].posxy.configured();
return config_in_storage;
return _configured;
}
// mark parameters as configured in storage (used to ensure parameter conversion is only done once)
void AP_NavEKF_Source::mark_configured_in_storage()
// mark parameters as configured (used to ensure parameter conversion is only done once)
void AP_NavEKF_Source::mark_configured()
{
// save first parameter's current value to mark as configured
return _source_set[0].posxy.save(true);

8
libraries/AP_NavEKF/AP_NavEKF_Source.h

@ -85,10 +85,10 @@ public: @@ -85,10 +85,10 @@ public:
bool usingGPS() const;
// true if source parameters have been configured (used for parameter conversion)
bool configured_in_storage();
bool configured();
// mark parameters as configured in storage (used to ensure parameter conversion is only done once)
void mark_configured_in_storage();
// mark parameters as configured (used to ensure parameter conversion is only done once)
void mark_configured();
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
// requires_position should be true if horizontal position configuration should be checked
@ -119,5 +119,5 @@ private: @@ -119,5 +119,5 @@ private:
AP_Int16 _options; // source options bitmask
uint8_t active_source_set; // index of active source set
bool config_in_storage; // true once configured in storage has returned true
bool _configured; // true once configured has returned true
};

Loading…
Cancel
Save