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

EKF2 local position stops following vision position while platform is moving #10310

Closed
ArkadiuszNiemiec opened this issue Aug 23, 2018 · 11 comments

Comments

@ArkadiuszNiemiec
Copy link
Contributor

ArkadiuszNiemiec commented Aug 23, 2018

I have a vision position system using ZED camera and companion computer connected via ROS. ZED wrapper publishes Odometry message so I wrote a simple script that relays this to mavros PoseStamped topic with rospy.Time.now() in header.
My camera is roughly 20 cm to the front of the Pixhawk.

Steps I did to test it:
Flash 1.8.0 with EKF2, turn off GPS in EKF2_AID_MASK, set EKF2_MAG_TYPE to None calibrate etc. set EKF2_EV_DELAY to 50 ms, EKF2_EVA_NOISE to 0.02 rad and EKF2_EVP_NOISE to 0.01 m.

It looks good when the platform is static, I can see LOCAL_POSITION_NED following the VISION_POSITION_ESTIMATE but when I start moving the platform it diverges, resets and then follows it again.

I have checked frames (ZED publishes in ENU, mavros takes ENU and converts it to NED before publishing mavlink message). How to debug this problem? Is my configuration wrong? ZED sets yaw to 0 when script starts, so maybe there's a problem that vision yaw is not equal to compass yaw? But then I have turned a mag in EKF2..

I have tried to set EKF2_EV_POS_X to +0.2 m but then the vision_position is rejected from the start.

Example logs: https://review.px4.io/plot_app?log=1107b173-7944-4d97-b015-7e8b4cfc2da1

@ArkadiuszNiemiec
Copy link
Contributor Author

I have forced it to work constantly by increasing EKF2_ev_GATE from 5.0 SD to 10.0 SD.

@mhkabir
Copy link
Member

mhkabir commented Aug 23, 2018

Please post a log with logging enabled from boot.

@tiralonghipol
Copy link

Hi. Any news on this? I am having the same behaviour!

@ArkadiuszNiemiec
Copy link
Contributor Author

@mhkabir I will post it next week, I am out of the office.
@tiralonghipol I made it work by playing with EKF2_EV_GATE but it made the EKF trust vision position even if it is clearly broken. I will try to lower it later and ask @mhkabir to help me debug the problem further.

@tiralonghipol
Copy link

yeah, I followed the same steps and the result is the same
I'll let you know if I have any improvement

@ArkadiuszNiemiec
Copy link
Contributor Author

ArkadiuszNiemiec commented Aug 28, 2018

@mhkabir Ok, I set the EKF2_EV_GATE to the default value and recorded a log from the boot. I was moving the unarmed platform in my arms.

https://logs.px4.io/plot_app?log=4742431c-320c-47b9-8130-c9f93ab75933

@tiralonghipol
Copy link

@mhkabir what is your current setup?
are you feeding /mavros/vision_pose/pose with what?

@priseborough
Copy link
Contributor

@ArkadiuszNiemiec

I have the following observations looking at your log:

  1. The EKF2_EVP_NOISE parameter setting of 0.01 m is much too low and will lead to the external vision data being rejected at circa 0.05 m of difference to the inertial nav solution. Start at 0.2m.

The ekf assumes the largest of EKF2_EVP_NOISE and eph.epv values and the vehicle_vision_position message in the log has a zero for eph and epv. A recent change pushed to ecl master PX4/PX4-ECL@2354c30 will enable separate horizontal and vertical accuracies when the corresponding PX4/Firmware changes are made.

  1. The EKF2_EVA_NOISE value of 0.02 is also too small. It should be no smaller than 0.05 looking at the innovations.

  2. If inertial errors continue to dominate, try doubling EKF2_GYR_NOISE and EKF2_ACC_NOISE .

  3. The output predictor will track more accurately if the buffer delay is kept short. Currently your buffer size is being determined by two sensors you don't use - GPS and Airspeed. Reduce these to 0 if you are not planning on using them.

  4. EKF2_MIN_OBS_DT is currently set to 20 so if the vision position message rate is greater than 50Hz there is a risk of messages being overwritten in the buffer before they are consumed by the ekf.

@ArkadiuszNiemiec
Copy link
Contributor Author

@priseborough @mhkabir thank you for your help, I have changed few parameters according to your suggestions but I left the EKF2_EV_GATE at 10 SD to make sure that it does not reject vision estmiation.

I have also tuned the UAV to poshold on GPS and I was very happy with results but when flying without a GPS and only on EV it starts to oscilate. Could you tell me how to tune it or is there any other step that I missed? Is my vision data bad or delayed?
Logs: https://logs.px4.io/plot_app?log=97adf845-91a0-4b18-a73c-be4a9d5116d0

@stale
Copy link

stale bot commented Jan 20, 2019

This issue has been automatically marked as stale because it has not had recent activity. It will be closed if no further activity occurs. Thank you for your contributions.

@stale
Copy link

stale bot commented Feb 4, 2019

Closing as stale.

@stale stale bot closed this as completed Feb 4, 2019
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

4 participants