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

Takeoff Revision #12014

Merged
merged 18 commits into from
May 22, 2019
Merged

Takeoff Revision #12014

merged 18 commits into from
May 22, 2019

Conversation

MaEtUgR
Copy link
Member

@MaEtUgR MaEtUgR commented May 13, 2019

Describe problem solved by the proposed pull request
Addressed Problems:

  1. The ramp logic was completely broken, see Fix Smooth Takeoff #12001
  2. The ramp didn't start at the correct value depending on vertical velocity control tuning
  3. The ramp didn't stop at the correct value when providing velocity and position setpoints during takeoff (which smooth mission does)
  4. The takeoff could be triggered accidentally when the state estimation fluctuates during idling
  5. There was a race condition when starting a takeoff while being disarmed in manual mode but with the throttle stick not at the minimum. In this case the takeoff was completely skiped and it jumped up very agressively.
  6. The whole logic was scattered over the position control module and very hard to debug

Describe your preferred solution

  1. I restored the original logic in Fix Smooth Takeoff #12001 but faced all the other listed problems and therefore continued in this pr.
  2. The ramp now starts at the precalculated verticalvelocity setpoint that will result in a thrust setpoint starting at zero value. see generateInitialValue() in the code.
  3. The ramp now stops at the velocity limit given by the constraint that will anyways be used during flight and is applied to the sum of the position controller output and velocity setpoint feed forward. see _takeoff.updateRamp(_dt, constraints.speed_up) where the constraint is now the goal value of the ramp.
  4. The initial idea of the flight task architecture was that a task can freely set it's setpoints and doesn't have to worry about takeoff and landing. It would just takeoff when it's landed and there's a setpoint to go up and land when it puts a setpoint that pushes into the ground. With the takeoff logic there are some significant interface problems depending on the way a task is implemented: From the setpoint is not high enough to trigger the takeoff to an unexpected takeoff because of some estimator fluctuation is affecting the setpoint.
    It's solved by allowing the task to determine when a takeoff is triggered. If no condition is implemented by default a task is not allowing a takeoff and cannot be used to get the vehicle off the ground.
    See the constraints.want_takeoff flag determined by the task to allow a takeoff, it's ignored in flight.
  5. As a hotfix I cut the throttle value when disarmed in manual mode. This is an in between solution and we should be able to remove it again when we allow a task to run when disarmed such that it already prepares the right setpoints.
  6. To even make it workable solving all these problems I created a Takeoff class which runs contains a state machine originally designed by @RomanBapst and @bresch and the ramp. This makes it a lot clearer what is takeoff logic and not other in flight logic. Also the state machine makes debugging very easy because when you look at the state and the single condition that blocks/skips you know exactly what goes wrong. It also prevents certain corner cases. Probably even 5., that has to be tested.

Test data / coverage
I SITL tested and real world tested all the changes in between and that's also how I found all the unexpected additional problems. The last commit is not real world tested yet so that needs to be carefully done. I'll update when I arrived to test it.

Additional context
old pr to fix for smooth takeoff: #12001

@MaEtUgR MaEtUgR requested review from Stifael and bresch May 13, 2019 19:14
@MaEtUgR MaEtUgR self-assigned this May 13, 2019
@MaEtUgR
Copy link
Member Author

MaEtUgR commented May 14, 2019

CI was very useful and found some initialization and offboard issues. I fixed them.

@MaEtUgR MaEtUgR force-pushed the task-based-takeoff-trigger branch from 0901160 to 813f5e7 Compare May 14, 2019 07:06
bool FlightTaskManualAltitude::_checkTakeoff()
{
// stick is is deflected up
return _sticks(2) > 0.65f;
Copy link
Contributor

Choose a reason for hiding this comment

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

in this case the flag want_to_takeoff is always true?

Copy link
Member Author

Choose a reason for hiding this comment

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

Yes, but it gets ignored when you're already flying.

@Stifael
Copy link
Contributor

Stifael commented May 14, 2019

Since the takeoff logic is anyway moved into flighttask, another alternative is to let flighttask know about the landing state. Then the takeoff-logic does no longer be split between flighttask- and mc-pos-control-main file.

@MaEtUgR MaEtUgR mentioned this pull request May 14, 2019
@MaEtUgR MaEtUgR force-pushed the task-based-takeoff-trigger branch from 844d980 to 7d49c6d Compare May 14, 2019 17:18
@MaEtUgR MaEtUgR changed the title Trigger takeoff based on task [WIP] Trigger takeoff based on task May 15, 2019
@MaEtUgR
Copy link
Member Author

MaEtUgR commented May 15, 2019

@Stifael Thanks a lot for having a look and the valuable input! Note that the thrust ramp I'm currently testing now has the correct coordinate frame. It's a good idea to inform the task of the takeoff state since we can then probably get rid of the reactive problems.

I'm continuing to further improve the takeoff on this branch since #12001 is the minimum viable solution release blocker.

@MaEtUgR
Copy link
Member Author

MaEtUgR commented May 15, 2019

I rebased on the hotfixes #12001 (comment)

I'm working on a takeoff class that has a state machine for the vehicle to stage by stage pass through (credit to @RomanBapst for that part!) and does a nice thrust ramp. Here's an example takeoff landing with the jerk limited trajectory auto implementation (default):
Takeoff class
Commiting the first version soon.

EDIT: Works good in SITL with auto and manual in all the cases I came up with. I'll test it on a real vehicle tomorrow.

@MaEtUgR MaEtUgR force-pushed the task-based-takeoff-trigger branch from 2f6c03a to 3876f63 Compare May 15, 2019 16:53
@MaEtUgR MaEtUgR changed the title [WIP] Trigger takeoff based on task [WIP] Takeoff Revision May 15, 2019
@MaEtUgR MaEtUgR force-pushed the task-based-takeoff-trigger branch from 3876f63 to 4b6ad6c Compare May 16, 2019 05:36
@MaEtUgR MaEtUgR mentioned this pull request May 16, 2019
@MaEtUgR
Copy link
Member Author

MaEtUgR commented May 16, 2019

Real world testing revealed a problem. Please hold back of any real-world testing until I fixed them.

MaEtUgR and others added 12 commits May 16, 2019 22:05
There were two rather confusing function calls one to check
if smooth takeoff needs to be ran and one that updates it.
I combined them and documented the interface correctly
making the parameters non-reference const floats.
The comments and variable names were partly misleading.
I grouped all members, hopefully gave them more
understandable names and adjusted the comments.
- start from a velocity setpoint pushing into the ground
to ramp from idle thrust up.
- start with a bit higher velocity setpoint threshold to make
sure the vehicle has a chance to really get off the ground.
- calculate ramp slope from initialization setpoint to the desired one
instead from zero to the desired. this ramps up quicker when you demand
a very small upwards velocity like the AutoLineSmoothVel and
ManualPositionSmoothVel tasks do at the beginning.
- don't stay in the takeoff ramp depending on the land detector, this
is unnecessary.
After boot the user is in manual mode and if he has an RC
but doesn't switch out the thrust gets set to the throttle stick
position. When he then starts a takeoff from tablet the thrust is still
high while arming and the land detector immediately sees a takeoff
skiping smooth takeoff from the position controller.
The initial idea of the flight task architecture was that
a task can freely set it's setpoints and doesn't have to
worry about takeoff and landing. It would just takeoff
when it's landed and there's a setpoint to go up and
land when it puts a setpoint that pushes into the ground.
With the takeoff logic there are some significant interface
problems depending on the way a task is implemented:
From the setpoint is not high enough to trigger to
an unexpected takeoff because of some estimator
fluctuation affecting the setpoint. It's easiest to solve this
by allowing the task to determine when a takeoff is triggered.
If no condition is implemented by default a task is not
allowing a takeoff  and cannot be used to get the vehicle
off the ground.
…activate z axis with downward velocity to takeoff smoothly
The velocity ramp had problems with:
- different vehicle tunings resulted in the start value of the resulting
thrust ramp staring either higher and lower than zero thrust.
lower -> delay of beginning
higher -> small jump at beginning
- when a task set position and velocity at the same time during takeoff
(which AutoSmoothVel does) it resulted in a velocity setpoint
jump at the end of the ramp because the additional velocity
setpoint correction from the position controller was not considered.

The thrust ramp should now be very deterministic:
- always start at zero
- always end at the curreant thrust setpoint output
of the complete position controller
In a deterministic way with clear states to go through.
There are two local_position_setpoint in the position controller.
One describing the setpoint the task gives to the position controller
and a second one with the output of the position controller. I corrected
the wrong one during takeoff because the new takeoff thrust ramp runs after
the controller and not before.
@MaEtUgR MaEtUgR force-pushed the task-based-takeoff-trigger branch from 64e0d86 to dfe355f Compare May 16, 2019 20:25
@LorenzMeier
Copy link
Member

Awesome, thanks!

@MaEtUgR
Copy link
Member Author

MaEtUgR commented May 17, 2019

I wasn't entirely pleased with the pure thrust ramp because for some part of the ramp up time the vehicle ramps nicely but at some point the drone accelerates up quite quickly. Ramping the thrust while the vehicle is still on ground makes sense since it's not yet moving up anyways but as soon as the vehicle left the ground ramping further to reach the current thrust setpoint results in linearly ramping the acting vertical acceleration and hence the vertical velocity goes up quadratic. This rapid increase in velocity is audible and visible and looks like an aggressive maneuver just after leaving the ground. The velocity ramp results in a thrust ramp while the vehicle is still on the ground (zero velocity) but as soon as the vehicle is moving and the estimated vertical velocity changes the controller takes care of not shooting up but rather going up with constant acceleration until the takeoff speed is met.

Early this morning I had good ideas how to resolve the issues we faced with the velocity ramp and implemented them in the last commit.

  • When to begin the ramp?
    There's a calculation now for the velocity ramp initial value such that the resulting thrust is zero at the beginning. The result is a fixed real-world takeoff time independent of the vehicle tuning assuming it's able to at least loosely track a velocity setpoint with it's tuning.
  • When to end the ramp?
    The ramp is applied to the upwards velocity constraint and it just ramps from the initial value to the velocity constraint which is applied during flight. Slower/going down is always possible. The problem we faced with the AutoVelSmooth task which generates a position setpoint and a velocity feed forward was that we used only the feed forward to determine when the ramp is finished. But since the vertical velocity constraint gets applied to the sum inside the position controller and there's always a maximum velocity constraint we can just ramp the constraint up linearly until it's at the value it anyways has during flight.

@bresch @RomanBapst Since I don't have a vehicle at hand does aynone dare to test this on the real vehicle? I tested in SITL and it all looks good. I also checked that the only horizontal thrust leading to 90 desired tilt which screwed me yesterday is not happening anywhere.

@RomanBapst
Copy link
Contributor

Will test!

@MaEtUgR MaEtUgR added this to the Release v1.9.0 milestone May 18, 2019
@MaEtUgR
Copy link
Member Author

MaEtUgR commented May 18, 2019

I updated the description such that we are all on the same page, sorry for not doing that earlier. The test of the last commit is still pending.

@RomanBapst
Copy link
Contributor

@MaEtUgR I will get to test this either today or tomorrow.

@LorenzMeier
Copy link
Member

@RomanBapst Keep us posted! The last item blocking the release!

@MaEtUgR
Copy link
Member Author

MaEtUgR commented May 20, 2019

I'm looking for a hole in the rain to get this tested for the entire day already but there's no chance 🌧

@dagar dagar requested a review from a team May 20, 2019 13:46
But fix the two crucial problems:
- When to begin the ramp?
There's a calculation now for the velocity ramp initial value
such that the resulting thrust is zero at the beginning.
- When to end the ramp?
The ramp is applied to the upwards velocity constraint and it
just ramps from the initial value to the velocity constraint
which is applied during flight. Slower/going down is always possible.
@MaEtUgR MaEtUgR force-pushed the task-based-takeoff-trigger branch from 11cdea4 to 0ace048 Compare May 20, 2019 18:23
@jorge789
Copy link

Indoor flight test on Pixhawk 2 Cube V3

Modes Tested

Takeoff: Good
Stabilized Mode: Good.

Pre-flight Procedure:

Flight Test:
Arm and Take off in the stabilized mode ✓
Throttle Test ✓
Pitch, Roll, Yaw ✓
Land ✓

Notes: Armed and took off in stabilized mode, flew for 30 seconds approximately then proceeded to land and disarm. This process was repeated one after another to a total of 5 take offs.

Flight log:
https://review.px4.io/plot_app?log=51dd999e-b62b-49df-955e-c4db61ff2e3e

Indoor flight test on PixRacer V4

Modes Tested

Takeoff: Good
Stabilized Mode: Good.

Pre-flight Procedure:

Flight Test:
Arm and Take off in the stabilized mode ✓
Throttle Test ✓
Pitch, Roll, Yaw ✓
Land ✓

Notes: Armed and took off in stabilized mode, flew for 30 seconds approximately then proceeded to land and disarm. This process was repeated one after another to a total of 5 take offs.

Flight log: 1
https://review.px4.io/plot_app?log=5318fe9f-d710-46b5-b6d5-4a6119d41d81

Flight log: 2
https://review.px4.io/plot_app?log=4c82cb60-a950-47c3-a993-f6f54d2355da

@dannyfpv
Copy link

dannyfpv commented May 20, 2019

Tested on Pixhawk 4 v5
Indoor test
Modes Tested

Takeoff: Good
Stabilized Mode: Good.

Flight Test:
Arm and Take off in the stabilized mode no issue
Throttle Test no issue
Pitch, Roll, Yaw no issue
Land no issue

Notes: Armed and took off in stabilized mode, flew for 30 seconds approximately then proceeded to land and disarm. This process was repeated one after another to a total of 5 take offs.

Logs:
https://review.px4.io/plot_app?log=2a63b1ed-0800-4b97-8913-f943b37c6793

https://review.px4.io/plot_app?log=025c0d46-cbd5-4fe4-b735-1d7aa25cd17d

@MaEtUgR
Copy link
Member Author

MaEtUgR commented May 21, 2019

When it was not raining for a moment @RomanBapst and I went out and did a couple of tests:
https://drive.google.com/file/d/12IFqDlUiIoZwSqX32CW4kz_79VtkRYFN

Generally the takeoff worked really well. We found two remaining smaller issues:

  • When the controller wants to correct sideways the vehicle does that as soon as possible directly when lifting off. This was intentionally to not have any drift at the beginning or discontiuous change in air but could depending on the use case be seen as an issue.
  • 0c81a19 only fixes the high thrust at the beginning problem described here: Fix Smooth Takeoff #12001 (comment) when starting in manual mode. There are very specific corner cases in which you might disarm with higher than idle thrust and then the thrust setpoint stays like this because no task is running and the setpoint does not get published until the pilot arms again. The first setpoint sample then still has the value from before it last disarmed. But it cannot as a result accidentally take off anymore because of the consistent takeoff state machine. I checked the log and it's not even visible there probably because the sample is still there from being disarmed and the first armed one is already low again.

Copy link
Contributor

@RomanBapst RomanBapst left a comment

Choose a reason for hiding this comment

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

@MaEtUgR Overall great job! I just have a few minor comments mostly about comments and naming.

_trajectory[i].reset(0.f, 0.f, _position(i));
}

_trajectory[2].reset(0.f, 0.7f, _position(2));
Copy link
Contributor

Choose a reason for hiding this comment

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

@bresch @MaEtUgR Do we still need this magic value?

Copy link
Member Author

@MaEtUgR MaEtUgR May 22, 2019

Choose a reason for hiding this comment

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

It was added to work nicer with the takeoff logic but should actually not matter anymore. We can do tests without it and see if it matters but I would suggest to just leave it for now.

src/lib/FlightTasks/tasks/FlightTask/FlightTask.cpp Outdated Show resolved Hide resolved
@MaEtUgR
Copy link
Member Author

MaEtUgR commented May 22, 2019

I consider it ready to merge.

@MaEtUgR MaEtUgR changed the title [WIP] Takeoff Revision Takeoff Revision May 22, 2019
@LorenzMeier LorenzMeier merged commit ea48cd4 into master May 22, 2019
@LorenzMeier LorenzMeier deleted the task-based-takeoff-trigger branch May 22, 2019 20:05
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

7 participants