mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_NavEKF_Source: add mark_configured_in_storage
This commit is contained in:
parent
50b2cf136f
commit
0119c48e1e
@ -293,13 +293,17 @@ bool AP_NavEKF_Source::usingGPS() const
|
||||
}
|
||||
|
||||
// true if some parameters have been configured (used during parameter conversion)
|
||||
bool AP_NavEKF_Source::any_params_configured_in_storage() const
|
||||
bool AP_NavEKF_Source::configured_in_storage() const
|
||||
{
|
||||
return _source_set[0].posxy.configured_in_storage() ||
|
||||
_source_set[0].velxy.configured_in_storage() ||
|
||||
_source_set[0].posz.configured_in_storage() ||
|
||||
_source_set[0].velz.configured_in_storage() ||
|
||||
_source_set[0].yaw.configured_in_storage();
|
||||
// first source parameter is used to determine if configured or not
|
||||
return _source_set[0].posxy.configured_in_storage();
|
||||
}
|
||||
|
||||
// mark parameters as configured in storage (used to ensure parameter conversion is only done once)
|
||||
void AP_NavEKF_Source::mark_configured_in_storage()
|
||||
{
|
||||
// save first parameter's current value to mark as configured
|
||||
return _source_set[0].posxy.save(true);
|
||||
}
|
||||
|
||||
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
|
||||
|
@ -82,8 +82,11 @@ public:
|
||||
// true if any source is GPS
|
||||
bool usingGPS() const;
|
||||
|
||||
// true if any primary source parameters have been configured (used for parameter conversion)
|
||||
bool any_params_configured_in_storage() const;
|
||||
// true if source parameters have been configured (used for parameter conversion)
|
||||
bool configured_in_storage() const;
|
||||
|
||||
// mark parameters as configured in storage (used to ensure parameter conversion is only done once)
|
||||
void mark_configured_in_storage();
|
||||
|
||||
// returns false if we fail arming checks, in which case the buffer will be populated with a failure message
|
||||
bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const;
|
||||
|
Loading…
Reference in New Issue
Block a user