Skip to content

Commit 0119c48

Browse files
committed
AP_NavEKF_Source: add mark_configured_in_storage
1 parent 50b2cf1 commit 0119c48

File tree

2 files changed

+15
-8
lines changed

2 files changed

+15
-8
lines changed

libraries/AP_NavEKF/AP_NavEKF_Source.cpp

Lines changed: 10 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -293,13 +293,17 @@ bool AP_NavEKF_Source::usingGPS() const
293293
}
294294

295295
// true if some parameters have been configured (used during parameter conversion)
296-
bool AP_NavEKF_Source::any_params_configured_in_storage() const
296+
bool AP_NavEKF_Source::configured_in_storage() const
297297
{
298-
return _source_set[0].posxy.configured_in_storage() ||
299-
_source_set[0].velxy.configured_in_storage() ||
300-
_source_set[0].posz.configured_in_storage() ||
301-
_source_set[0].velz.configured_in_storage() ||
302-
_source_set[0].yaw.configured_in_storage();
298+
// first source parameter is used to determine if configured or not
299+
return _source_set[0].posxy.configured_in_storage();
300+
}
301+
302+
// mark parameters as configured in storage (used to ensure parameter conversion is only done once)
303+
void AP_NavEKF_Source::mark_configured_in_storage()
304+
{
305+
// save first parameter's current value to mark as configured
306+
return _source_set[0].posxy.save(true);
303307
}
304308

305309
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message

libraries/AP_NavEKF/AP_NavEKF_Source.h

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -82,8 +82,11 @@ class AP_NavEKF_Source
8282
// true if any source is GPS
8383
bool usingGPS() const;
8484

85-
// true if any primary source parameters have been configured (used for parameter conversion)
86-
bool any_params_configured_in_storage() const;
85+
// true if source parameters have been configured (used for parameter conversion)
86+
bool configured_in_storage() const;
87+
88+
// mark parameters as configured in storage (used to ensure parameter conversion is only done once)
89+
void mark_configured_in_storage();
8790

8891
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
8992
bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const;

0 commit comments

Comments
 (0)