Local Position only Takeoff Problems for Multicopter
Describe the bug
In local position only flight of multicopter, Takeoff & Land exhibit very dangerous behavior If you move vehicle after initialization, trying to land or takeoff again after moving The vehicle tries to go back to local position (x,y) = (0,0) when takeoff & landing wherever the vehicle is
To Reproduce
Problem can be reproduced using Gazebo Classic SITL with IRIS Vision model
- Remove GPS in Gazebo Classic IRIS model - comment out these lines or the generated corresponding sdf file
- Make sure to set parameters EKF2_MAG_TYPE = 4 (MC Custom) & EKF2_GPS_CTRL = 0 to fly without GNSS
- Take-off the vehicle (using Takeoff mode/task)
- Fly the vehicle anywhere using joystick
- Land the vehicle (using Land mode/task)
- Try to take-off the vehicle again
Expected behavior
In reproduction step 5, vehicle tries to fly to where it took off, may crash due to horizontal velocity In reproduction step 6, also vehicle tries to fly back to local origin (0, 0, MIS_TAKEOFF_ALT)
Log Files and Screenshots
https://logs.px4.io/plot_app?log=4dfb850c-2472-45a0-bafb-4c779f64091a

The vehicle rapidly goes back to the local origin when try to land or take-off, ended-up crash at 2nd land trial without having enough altitude to go back to local origin
Drone (please complete the following information):
Quadcopter - Gazebo-Classic IRIS Vision with GPS removed as in reproduction step 1 & 2
Additional Information
As far as I debugged into, this problem could be resolved by adding check to the FlightTaskAuto::_evaluateTriplets() in my case alone
if (!_sub_vehicle_local_position.get().xy_global
|| !PX4_ISFINITE(_sub_triplet_setpoint.get().current.lat)
|| !PX4_ISFINITE(_sub_triplet_setpoint.get().current.lon))
using xy_global flag in the VehicleLocalPosition uORB message, which is set in EKF when global origin is valid, only set to true in Ekf::collect_gps() with GPS data input
This problem could not be caught with PX4_ISFINITE() check, since zero initialized global reference(class MapProjection) in EKF2 is just zeroes - finite & sane value and using that value like here is just passing zeroes to the FlightTask
Having the same issue https://review.px4.io/plot_app?log=fea310f4-badc-4735-88c4-9cf4399126b2
Re-open this issue because Takeoff is not fixed yet. It always goes to (0,0) when taking off without global position. How to reproduce in simulation:
- disable GPS (e.g. in SimulationMavlink)
- takeoff manually and fly somewhere
- descend to 1m
- switch into Takeoff mode --> drone climbs to default takeoff altitude and flies to the origin (0,0)
The Takeoff mode seems to send a positionsetpoint of lat=0, lon=0. I would have expected it to send NAN, such that the FlightTask can handle it, as it is written in a comment as well.
FYI @MaEtUgR
Hello @sfuhrer,
I hope you’re doing well. I was facing the same problem, just want to check if there has been any progress on the takeoff issue you mentioned. I would be happy to help—please let me know if there’s anything I can do.
Thank you!
Hello @sfuhrer,
I hope you’re doing well. I was facing the same problem, just want to check if there has been any progress on the takeoff issue you mentioned. I would be happy to help—please let me know if there’s anything I can do.
Thank you!
Hi @tedlin0913 ! No, I guess nothing has changed since, and if you would be able to help out that would be awesome!