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

FlightTaskAutoLineSmoothVel: generate trajectory does not override th… #13093

Closed

Conversation

dusan19
Copy link
Contributor

@dusan19 dusan19 commented Oct 4, 2019

…e NAN position setpoints

In case we want to control the drone by setting the velocities, we set the position setpoint to NAN.
FlightTaskAutoLineSmoothVel::_generateTrajectory() overrides this NAN setpoints which causes the position controller to control position rather than the velocity directly.

I noticed this when I checked for the landing velocity setpoints. The setpoint was set to be the one set by the parameter, and the position sp was set to NAN, but this was overridden with an another value, and the drone didn't land with the desired velocity but hit the ground very hard.

This pr simply fixes the problem by checking if the position sp is NAN before overriding it.
I tested the landing case, and the z velocity setpoint was set properly to match the landing speed defined with the parameter.

@bresch
Copy link
Member

bresch commented Oct 18, 2019

Unfortunately setting the position to NAN only hides the problem as the internal state is not reset and if the input is not NAN, the generated position can be quite far. The other problem is that opening and closing the position loop requires careful handling to ensure smoothmess of the setpoints (see FlightTaskManualPositionSmoothVel).

I also don't think that the position setpoint is the root cause of your hard landing as the position setpoint is simply the exact integral of the velocity one. It won't make your drone fly faster if the tracking is correct.
The hard landing is most likely caused by:

  • poor altitude/velocity tuning
  • problems of the altitude/velocity estimation
  • too high acceleration/jerk settings on the vertical axis

Could you please share a log so we can see together where the problem is and what would be the appropriate solution?

@dusan19
Copy link
Contributor Author

dusan19 commented Oct 22, 2019

Unfortunately setting the position to NAN only hides the problem as the internal state is not reset and if the input is not NAN, the generated position can be quite far.

Not sure I get this. Here I am only setting the position setpoint output to NAN if it was NAN already before generating the trajectory. Internally the trajectory and all states would still be computed in the same way, just the generated position sp would be set to NAN such that the position controller controls the velocities directly.

as the position setpoint is simply the exact integral of the velocity one

That's a good point

too high acceleration/jerk settings on the vertical axis

FMI, what kind of problems do high jerk settings cause, wouldn't in that case the velocity setpoints just be less smooth and allow for aggressive flight?

Here is the log:
https://review.px4.io/plot_app?log=20ebba24-ca5e-4424-8ba0-16dfe72d493e

If you look at the vehicle_local_position_setpoint/vz you can see that it reaches 1m/s (which the estimated velocity follows) while the trajectory/vz is constant 0.6m/s during the whole landing part.

@bresch
Copy link
Member

bresch commented Nov 11, 2019

Not sure I get this. Here I am only setting the position setpoint output to NAN if it was NAN already before generating the trajectory. Internally the trajectory and all states would still be computed in the same way, just the generated position sp would be set to NAN such that the position controller controls the velocities directly.

Let's imagine that during the descent, the position of the trajectory is ignored and that the tracking isn't great such that the internal state is at 0 meters but the drone is still at 5 meters above ground. If the landing is aborted, the position setpoint won't NAN anymore and suddenly the position of the trajectory is 5 meters below the drone. This is why if you want to do that, you absolutely need to reset the position of the trajectory if you are not using it.

FMI, what kind of problems do high jerk settings cause, wouldn't in that case the velocity setpoints just be less smooth and allow for aggressive flight?

Yes, but if the jerk/accel parameters are higher than what the drone can do, the drone will not be able to track the trajectory properly.

If you look at the vehicle_local_position_setpoint/vz you can see that it reaches 1m/s (which the estimated velocity follows) while the trajectory/vz is constant 0.6m/s during the whole landing part.

The velocity setpoint reaches 1m/s because the altitude tracking is bad. The clean way to solve this is to improve the tuning of your velocity/position controller. If you see that it cannot be tuned well, you might need to check the quality of the velocity estimate (innovations).
2019-11-11_16-06-06_01_plot

@bresch bresch closed this Nov 11, 2019
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants