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

Hover thrust estimator #13981

Merged
merged 4 commits into from
Feb 7, 2020
Merged

Hover thrust estimator #13981

merged 4 commits into from
Feb 7, 2020

Conversation

bresch
Copy link
Member

@bresch bresch commented Jan 19, 2020

Describe problem solved by this pull request
The hover thrust is an important parameter of the vehicle that is used during flight for altitude control and to detect landing. It needs to be set manually by the user (MPC_THR_HOVER), and can trigger a crash if wrongly set.

Furthermore, this parameter is constant, but In reality, the real hover thrust is not:

  • The battery voltage decreases during the flight -> requires more throttle if RPM isn't controlled by the ESC
  • The mass can change (e.g.: cargo drones, crop sprayers, ...)

Finally, some vehicles with many possible payloads can have a different hover thrust at almost every takeoff.

Describe your solution
Given the current thrust and the measured vertical acceleration, it is possible to observe the hover thrust. This is done in this PR using a simple single-state EKF.
The model is described and simulated here.

Describe possible alternatives
Some logic that tries to detect a hover to set the hover thrust as the current thrust.
A higher order model

Test data / coverage
Current state: SITL tests, the estimator converges to the correct value. When changing the mass during hover, the estimate follows quickly.

Additional context
Auterion/Flight_Control_Prototyping_Scripts#3

TODO:

  • unit tests!
  • log the state and main important values (variance, innov, test ratio, ...)
  • use the estimated hover thrust in PositionControl and the LandDetector edit: this will be done later
  • check dynamic response (up/down motions)
  • use unfiltered acceleration (edit: I'm using the acceleration in local frame from EKF2 and it seems to work quite well)
  • add thrust to acceleration dynamic model (first order filter should be enough) edit: not required, the performance is good enough
  • make sure it doesn't update during the ground contact phase

fixes #12439

Copy link
Contributor

@jkflying jkflying left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This looks awesome.

An idea, how about we already use the value of the estimated hover thrust if the parameter is set to 0? Then existing users won't be affected, but with a single parameter change can get the new behavior. We can set the default to 0 once we are happy with the performance.

Also, I'm very interested to see how the convergence speed is on initialization, compared to noise rejection over longer periods. There might be value in using vertical velocity estimate plus a drag model to improve accuracy - but I'm not sure if that will be necessary, since this is already a huge improvement over a single hardcoded value.

@@ -603,6 +607,11 @@ MulticopterPositionControl::Run()
_control.resetIntegral();
// reactivate the task which will reset the setpoint to current state
_flight_tasks.reActivate();
_hover_thrust_estimator.reset();

} else if (_takeoff.getTakeoffState() >= TakeoffState::flight) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do we need to handle landing as well to make sure it doesn't get corrupted? Or will this work for the landing case too?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good point, i would need to check that

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why is this in the else case? Would you want to run it if PX4_ISFINITE(setpoint.thrust[2])?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@bresch did you check this?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@mhkabir Yes, due to the high inconsistency at touchdown, the measurements are rejected until the recovery kicks-in and we should be able to detect landing in the mean time (using that inconsistency as a ground contact check).
About the "Why is this in the else case? Would you want to run it if PX4_ISFINITE(setpoint.thrust[2])?", I placed it in that else because it gets reset when on ground in the if above, so we don't need to do a double check. It might not be ideal but I can still change that when I use the output of the filter for feedforward and land detection.

/**
* Hover thrust process noise
*
* Bla
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@bresch Bla? :-D

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Isn't that clear enough? xD

@RomanBapst
Copy link
Contributor

@bresch Btw, I really like to use these lecture note as reference.
https://idsc.ethz.ch/education/lectures/recursive-estimation.html

I think it provides a really good summary in case you don't always want to read 1000 pages in the Kalman filter book.

Copy link
Contributor

@kamilritz kamilritz left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Great Work, I like the separation of the HoverThrustEstimator and ZeroOrderHoverThrustEstimator.
Are the local_pos_sp.thrust and _states.acceleration in local/world coordinates?

src/lib/hover_thrust_estimator/CMakeLists.txt Outdated Show resolved Hide resolved
src/lib/hover_thrust_estimator/HoverThrustEstimator.hpp Outdated Show resolved Hide resolved
src/lib/hover_thrust_estimator/ZeroOrderHoverThrustEkf.cpp Outdated Show resolved Hide resolved
src/lib/hover_thrust_estimator/ZeroOrderHoverThrustEkf.cpp Outdated Show resolved Hide resolved
src/lib/hover_thrust_estimator/ZeroOrderHoverThrustEkf.cpp Outdated Show resolved Hide resolved
src/lib/hover_thrust_estimator/ZeroOrderHoverThrustEkf.cpp Outdated Show resolved Hide resolved
src/lib/hover_thrust_estimator/ZeroOrderHoverThrustEkf.hpp Outdated Show resolved Hide resolved
@dagar
Copy link
Member

dagar commented Jan 21, 2020

If you rebase there's a big chunk of flash available on fmu-v2 now.

@bresch bresch force-pushed the pr-hover-ekf branch 2 times, most recently from e37ce88 to 5394248 Compare January 23, 2020 13:01
@bresch
Copy link
Member Author

bresch commented Jan 23, 2020

SITL jMavSim test where the weight of the vehicle is changed during flight from 0.4 to 0.8kg.
Initially the measurement is rejected (large test ratio) but then the measurement variance blows-up and the state slowly starts to converge towards the new true value. This way, no reset logic is required and the state is continuous.
2020-01-23_13-21-38_01_plot

@bresch
Copy link
Member Author

bresch commented Jan 23, 2020

@PX4/testflights Can you give that PR a quick try please? This is just for logging, don't expect anything different.

@bresch bresch requested a review from a team January 23, 2020 14:18
@Tony3dr Tony3dr added this to Ready for testing in Test Flights Jan 23, 2020
@Junkim3DR
Copy link

Tested on NXP FMUK66 v3

Modes Tested
Position Mode: Good.
Altitude Mode: Good.
Stabilized Mode: Good.
Mission Plan Mode (Automated): Good.
RTL (Return To Land): Good.

Procedure
Arm and Take off in position mode, after flying for approximately one minute, switched to altitude then stabilized mode proceed to switch to mission plan mode then make sure that vehicle follows all waypoints as shown in QGC, once completed all waypoint then trigger RTL.

Notes
No issues noted, good flight in general.

Log

@jorge789
Copy link

Tested on PixRacer V4

Modes Tested
Position Mode: Good.
Altitude Mode: Good.
Stabilized Mode: Good.
Mission Plan Mode (Automated): Good.
RTL (Return To Land): Good.

Procedure
Arm and Take off in position mode, after flying for approximately one minute, switched to altitude then stabilized mode proceed to switch to mission plan mode then make sure that vehicle follows all waypoints as shown in QGC, once completed all waypoint then trigger RTL.

Notes
No issues noted, good flight in general.

Log
https://review.px4.io/plot_app?log=64209608-53fe-4c6d-94bd-b92bf7109188

Tested on CUAV nano V5

Modes Tested
Position Mode: Good.
Altitude Mode: Good.
Stabilized Mode: Good.
Mission Plan Mode (Automated): Good.
RTL (Return To Land): Good.

Procedure
Arm and Take off in position mode, after flying for approximately one minute, switched to altitude then stabilized mode proceed to switch to mission plan mode then make sure that vehicle follows all waypoints as shown in QGC, once completed all waypoint then trigger RTL.

Notes
No issues noted, good flight in general.

Log
https://review.px4.io/plot_app?log=debc4edf-477d-4fde-a23c-661bebf8371c

@dannyfpv
Copy link

dannyfpv commented Jan 23, 2020

Tested on Pixhawk 4 V5 f-450
Modes Tested
Position Mode: Good.
Altitude Mode: Good.
Stabilized Mode: Good.
Mission Plan Mode (Automated): Good.
RTL (Return To Land): Good.

Procedure
Arm and Takeoff in position mode, after flying for approximately one minute, switched to altitude then stabilized mode proceeds to switch to mission plan mode then make sure that vehicle follows all waypoints as shown in QGC, once completed all waypoint then trigger RTL.

Notes
No issues noted, good flight in general.

Log
https://review.px4.io/plot_app?log=95d42940-52c1-409b-a458-3505ef91bd32

@bresch
Copy link
Member Author

bresch commented Jan 24, 2020

Thanks @Junkim3DR @dannyfpv and @jorge789 !

Copy link
Member

@MaEtUgR MaEtUgR left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Nice architecture with the interface class!

src/lib/hover_thrust_estimator/hover_thrust_estimator.hpp Outdated Show resolved Hide resolved
@@ -603,6 +607,11 @@ MulticopterPositionControl::Run()
_control.resetIntegral();
// reactivate the task which will reset the setpoint to current state
_flight_tasks.reActivate();
_hover_thrust_estimator.reset();

} else if (_takeoff.getTakeoffState() >= TakeoffState::flight) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why is this in the else case? Would you want to run it if PX4_ISFINITE(setpoint.thrust[2])?

@bresch
Copy link
Member Author

bresch commented Jan 28, 2020

@PX4/testflights could you make a few more flights please?

Multicopter automation moved this from In progress to Reviewer approved Feb 7, 2020
dagar
dagar previously approved these changes Feb 7, 2020
Multicopter automation moved this from Reviewer approved to Review in progress Feb 7, 2020
jkflying
jkflying previously approved these changes Feb 7, 2020
Copy link
Contributor

@jkflying jkflying left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM, tests all passing

Multicopter automation moved this from Review in progress to Reviewer approved Feb 7, 2020
with measurement noise auto-tuning

The purpose of this estimator is to improve land detection and vertical
velocity feedforward

Recovery strategy:
This is required when the setpoint suddenly changes in air or that the
EKF is diverging. A lowpassed test ratio is used as a trigger for the recovery logic
Also, a lowpassed residual is used to estimate the steady-state value
and remove it when estimating the accel noise to avoid increasing the
accel noise when the redisual is caused by an offset.
With noisy accel and thrust in hover, climb and descent conditions.
This is done to test the recovery function of the estimator in case
of divergence or sudden extreme hover thrust change.

Also specify seed of random generator
Multicopter automation moved this from Reviewer approved to Review in progress Feb 7, 2020
@@ -47,32 +47,37 @@ using namespace matrix;
class ZeroOrderHoverThrustEkfTest : public ::testing::Test
{
public:
ZeroOrderHoverThrustEkfTest()
{
_random_generator.seed(42);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

🙂

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Just FYI (and lessons learned from previous hair-pulling), these still won't be the same across platforms or std libraries... 😢

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@jkflying hmm, okay, should I run once the Gaussian noise generator and save the output in a file to be sure that we always use the same data?

Multicopter automation moved this from Review in progress to Reviewer approved Feb 7, 2020
@bresch bresch merged commit ca0b570 into master Feb 7, 2020
Test Flights automation moved this from Ready for testing to Done Feb 7, 2020
Multicopter automation moved this from Reviewer approved to Done Feb 7, 2020
@bresch bresch deleted the pr-hover-ekf branch February 7, 2020 10:52
@bresch
Copy link
Member Author

bresch commented Feb 7, 2020

Finally merged, thanks everyone for the help! :)

@VTOLDavid
Copy link
Contributor

What would happen in a VTOL in hover with wind? The hover thurst can be really low.

@bresch
Copy link
Member Author

bresch commented Jun 11, 2020

@VTOLDavid If it's a constant wind and the hover thrust is constantly lower, the estimator will converge to this new value. If it's just wind gusts, the estimator will reject that and keep the same value.
It's also a similar effect during VTOL transitions the hover thrust changes but it isn't an issue, the estimator has a recovery strategy that allows it to converge to a new estimate, even if far from the initial one.
You can do some SITL tests or check if you can find public VTOL logs to see how it behaves (check the hover_thrust_estimate topic).

@VTOLDavid
Copy link
Contributor

Thank you for the explanation.

@DronecodeBot
Copy link

This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/multicopter-with-1kg-payload-px4/39275/3

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
No open projects
Multicopter
  
Done
Test Flights
  
Done
Development

Successfully merging this pull request may close these issues.

Auto-estimate hover throttle