mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: remove use of uninitialised value
This commit is contained in:
parent
378bd84b29
commit
802206baed
@ -650,11 +650,14 @@ bool AP_AHRS_NavEKF::get_relative_position_NED(Vector3f &vec) const
|
|||||||
case EKF_TYPE3: {
|
case EKF_TYPE3: {
|
||||||
Vector2f posNE;
|
Vector2f posNE;
|
||||||
float posD;
|
float posD;
|
||||||
bool position_is_valid = (EKF3.getPosNE(-1,posNE) && EKF3.getPosD(-1,posD));
|
if (EKF3.getPosNE(-1,posNE) && EKF3.getPosD(-1,posD)) {
|
||||||
vec.x = posNE.x;
|
// position is valid
|
||||||
vec.y = posNE.y;
|
vec.x = posNE.x;
|
||||||
vec.z = posD;
|
vec.y = posNE.y;
|
||||||
return position_is_valid;
|
vec.z = posD;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
Loading…
Reference in New Issue
Block a user