Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_NavEKF3: initialise variables as part of declaration #28378

Merged
merged 1 commit into from
Oct 14, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
45 changes: 15 additions & 30 deletions libraries/AP_NavEKF3/AP_NavEKF3_AirDataFusion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,25 +20,19 @@
void NavEKF3_core::FuseAirspeed()
{
// declarations
ftype vn;
ftype ve;
ftype vd;
ftype vwn;
ftype vwe;
ftype SH_TAS[3];
ftype SK_TAS[2];
Vector24 H_TAS = {};
ftype VtasPred;

// copy required states to local variable names
vn = stateStruct.velocity.x;
ve = stateStruct.velocity.y;
vd = stateStruct.velocity.z;
vwn = stateStruct.wind_vel.x;
vwe = stateStruct.wind_vel.y;
const ftype vn = stateStruct.velocity.x;
const ftype ve = stateStruct.velocity.y;
const ftype vd = stateStruct.velocity.z;
const ftype vwn = stateStruct.wind_vel.x;
const ftype vwe = stateStruct.wind_vel.y;

// calculate the predicted airspeed
VtasPred = norm((ve - vwe) , (vn - vwn) , vd);
const ftype VtasPred = norm((ve - vwe) , (vn - vwn) , vd);
// perform fusion of True Airspeed measurement
if (VtasPred > 1.0f)
{
Expand Down Expand Up @@ -280,31 +274,22 @@ void NavEKF3_core::SelectBetaDragFusion()
void NavEKF3_core::FuseSideslip()
{
// declarations
ftype q0;
ftype q1;
ftype q2;
ftype q3;
ftype vn;
ftype ve;
ftype vd;
ftype vwn;
ftype vwe;
const ftype R_BETA = 0.03f; // assume a sideslip angle RMS of ~10 deg
Vector13 SH_BETA;
Vector8 SK_BETA;
Vector3F vel_rel_wind;
Vector24 H_BETA;

// copy required states to local variable names
q0 = stateStruct.quat[0];
q1 = stateStruct.quat[1];
q2 = stateStruct.quat[2];
q3 = stateStruct.quat[3];
vn = stateStruct.velocity.x;
ve = stateStruct.velocity.y;
vd = stateStruct.velocity.z;
vwn = stateStruct.wind_vel.x;
vwe = stateStruct.wind_vel.y;
const ftype q0 = stateStruct.quat[0];
const ftype q1 = stateStruct.quat[1];
const ftype q2 = stateStruct.quat[2];
const ftype q3 = stateStruct.quat[3];
const ftype vn = stateStruct.velocity.x;
const ftype ve = stateStruct.velocity.y;
const ftype vd = stateStruct.velocity.z;
const ftype vwn = stateStruct.wind_vel.x;
const ftype vwe = stateStruct.wind_vel.y;

// calculate predicted wind relative velocity in NED
vel_rel_wind.x = vn - vwn;
Expand Down
Loading