AP_NavEKF: fixed use of configured() vs configured_in_storage()
This commit is contained in:
parent
d5670ace3b
commit
72470e290c
@ -286,20 +286,20 @@ bool AP_NavEKF_Source::usingGPS() const
|
|||||||
}
|
}
|
||||||
|
|
||||||
// true if some parameters have been configured (used during parameter conversion)
|
// 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;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// first source parameter is used to determine if configured or not
|
// 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)
|
// mark parameters as configured (used to ensure parameter conversion is only done once)
|
||||||
void AP_NavEKF_Source::mark_configured_in_storage()
|
void AP_NavEKF_Source::mark_configured()
|
||||||
{
|
{
|
||||||
// save first parameter's current value to mark as configured
|
// save first parameter's current value to mark as configured
|
||||||
return _source_set[0].posxy.save(true);
|
return _source_set[0].posxy.save(true);
|
||||||
|
@ -85,10 +85,10 @@ public:
|
|||||||
bool usingGPS() const;
|
bool usingGPS() const;
|
||||||
|
|
||||||
// true if source parameters have been configured (used for parameter conversion)
|
// 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)
|
// mark parameters as configured (used to ensure parameter conversion is only done once)
|
||||||
void mark_configured_in_storage();
|
void mark_configured();
|
||||||
|
|
||||||
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
|
// 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
|
// requires_position should be true if horizontal position configuration should be checked
|
||||||
@ -119,5 +119,5 @@ private:
|
|||||||
AP_Int16 _options; // source options bitmask
|
AP_Int16 _options; // source options bitmask
|
||||||
|
|
||||||
uint8_t active_source_set; // index of active source set
|
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…
Reference in New Issue
Block a user