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
Wind & airspeed scale estimator #6386
Conversation
Validate with flights logging this, but not relying on it? Do you think it should be in ekf2 like this, or could it live in sensors/airspeed getting the velocity variance from the uorb message? |
Adding myself as a reviewer for testing, but someone that better understands the derivation should actually review. @priseborough would you mind reviewing? |
I would prefer for this to live in sensors/airspeed and include the differential pressure scale factor error as an additional state. It would then solve the calibration problem we have and also mean that the estimates are available if ecl is not loaded. |
@dagar @priseborough Sounds like a good idea. What do you think about the parameters? Do we need to share noise parameters with ekf2 or should we have separate params? (wind process noise, beta noise, airspeed noise) |
@Tumbili Can you fix CI / style failures? |
""" | ||
|
||
from sympy import * | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Glad to see the use of sympy. Any chance you can include an ipython notebook with the rendered equations? I think it would be worthwhile since github renders them.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@jgoppert I'll see what I can do. I never used ipython notebook before but I know it's cool.
@LorenzMeier @dagar @priseborough I'm happy to help fully integrate this based on the above comments. @priseborough mentioned that it should not depend on ekf2 (or ecl) which makes sense. The estimator needs the following data to run:
|
I think it would fit cleanly into a standalone module that also incorporates the true and indicated calculations. Then it could be the only publisher of airspeed. |
@dagar So if I understand you correctly you would move the entire diff pressure stuff out of the sensors module into a new one? Or are you rather talking about a class residing in the sensors module? |
Either way sounds acceptable to me, unless anyone objects to a scale estimator living in the sensors module? |
@priseborough Can you chime in here? |
I'm happy for it to go in the sensors module. If it is executed after the publishing of the sensors_combined topic, then it won't impact on latency for the attitude loops. |
@priseborough ok, I'll move it there then! |
dd278b3
to
00abea6
Compare
src/modules/ekf2/ekf2_main.cpp
Outdated
@@ -964,19 +964,19 @@ void Ekf2::task_main() | |||
} | |||
|
|||
// Publish wind estimate | |||
struct wind_estimate_s wind_estimate = {}; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@dagar @priseborough @LorenzMeier Need a solution for this.
@priseborough @dagar I moved the wind estimator to the sensors module. Above, you can see some plots from the three states and innovations + variances. This was tested in SITL when the plane was flying a circle. |
if (fuse_airspeed) { | ||
matrix::Vector3f vel_var(_control_state.vel_variance); | ||
vel_var = R_to_earth * vel_var; | ||
_wind_estimator.fuse_airspeed(_airspeed.indicated_airspeed_m_s, &vI._data[0][0], &vel_var._data[0][0]); |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@dagar @priseborough I used indicated airspeed here because "true airspeed" seems to be rubbish in SITL, very small values.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
needs a solution Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
Signed-off-by: Roman <bapstroman@gmail.com>
@Tumbili Can you rebase and update this? |
I tried this PR about two weeks ago and I wasn't able to calibrate the airspeed sensor anymore. Not completely sure if it was because of this PR, I only tried once. |
Closing in favor of rebased version: #7424 |
No description provided.