mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_NavEKF2: move getMagOffsets into outputs
This commit is contained in:
parent
acfaafe276
commit
1185cd1be7
@ -142,20 +142,6 @@ void NavEKF2_core::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRa
|
||||
* MAGNETOMETER *
|
||||
********************************************************/
|
||||
|
||||
// return magnetometer offsets
|
||||
// return true if offsets are valid
|
||||
bool NavEKF2_core::getMagOffsets(Vector3f &magOffsets) const
|
||||
{
|
||||
// compass offsets are valid if we have finalised magnetic field initialisation and magnetic field learning is not prohibited and primary compass is valid
|
||||
if (firstMagYawInit && (frontend->_magCal != 2) && _ahrs->get_compass()->healthy(magSelectIndex)) {
|
||||
magOffsets = _ahrs->get_compass()->get_offsets(magSelectIndex) - stateStruct.body_magfield*1000.0f;
|
||||
return true;
|
||||
} else {
|
||||
magOffsets = _ahrs->get_compass()->get_offsets(magSelectIndex);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// check for new magnetometer data and update store measurements if available
|
||||
void NavEKF2_core::readMagData()
|
||||
{
|
||||
|
@ -345,6 +345,20 @@ void NavEKF2_core::getMagXYZ(Vector3f &magXYZ) const
|
||||
magXYZ = stateStruct.body_magfield*1000.0f;
|
||||
}
|
||||
|
||||
// return magnetometer offsets
|
||||
// return true if offsets are valid
|
||||
bool NavEKF2_core::getMagOffsets(Vector3f &magOffsets) const
|
||||
{
|
||||
// compass offsets are valid if we have finalised magnetic field initialisation and magnetic field learning is not prohibited and primary compass is valid
|
||||
if (firstMagYawInit && (frontend->_magCal != 2) && _ahrs->get_compass()->healthy(magSelectIndex)) {
|
||||
magOffsets = _ahrs->get_compass()->get_offsets(magSelectIndex) - stateStruct.body_magfield*1000.0f;
|
||||
return true;
|
||||
} else {
|
||||
magOffsets = _ahrs->get_compass()->get_offsets(magSelectIndex);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// return the index for the active magnetometer
|
||||
uint8_t NavEKF2_core::getActiveMag() const
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user