Skip to content

Commit

Permalink
Version 5.4 commit - has updated attitude shifting in the ahrs algorithm
Browse files Browse the repository at this point in the history
  • Loading branch information
spencerdynojet committed Apr 9, 2019
1 parent 9df5016 commit 5695154
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 3 deletions.
2 changes: 1 addition & 1 deletion ExEFIS/ExEFIS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ int main(int argc, char *argv[])

/* Start some String outputs in case you are launching the app with loggint enabled */
qDebug("****************** LOG BEGINS HERE **************************");
qDebug("Version 5.3 - Added settings file and Attitude Adjust ");
qDebug("Version 5.4 - Added settings file and Attitude Adjust - added attitude offset for Filter ");

system("cat /proc/cpuinfo | grep Serial | cut -d ' ' -f 2");
system("gpio mode 26 out");
Expand Down
2 changes: 1 addition & 1 deletion ExEFIS/SKFilter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -436,7 +436,7 @@ bool SKFilter::update(float gx, float gy, float gz, float ax, float ay, float az
acState.turning = !axisstill.gyroyaw || !axisstill.magyaw;
acState.wingslevel = (!acState.turning && acState.ballcentered);
acState.oneG = (abs(1.0f - totalmag) <= 0.012f);
acState.pitchlevel = acState.oneG && acState.pitchstill && abs(_accelEuler[1] - attitudeOffset) < 0.02 && !acState.turning;
acState.pitchlevel = acState.oneG && acState.pitchstill && abs(_accelEuler[1] - attitudeOffset) < 0.05 && !acState.turning;


if (acState.pitchlevel)
Expand Down
3 changes: 2 additions & 1 deletion ExEFIS/adhrs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -495,7 +495,8 @@ void adhrs::setSteerToSettings(int* steerto)

void adhrs::setAttitudeOffset(int offset_deg)
{
hrs->setAttitudeOffset((float)(offset_deg*M_PI/180.0f));
//Note the negative here to account for the opposite of the level flag in the AHRS
hrs->setAttitudeOffset((float)(-offset_deg*M_PI/180.0f));
}


Expand Down

0 comments on commit 5695154

Please sign in to comment.