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] Indoor optical flow/Lidar Lite and Outdoor GPS/Optical Flow/Lidar Lite(Hand-held testing) #9206

Closed
wkyoun opened this issue Mar 31, 2018 · 10 comments

Comments

@wkyoun
Copy link

wkyoun commented Mar 31, 2018

@priseborough @mhkabir @dagar


[EKF2] Indoor optical flow/Lidar Lite


We have expensive device mounted on the UAV, thus we would like to make sure that
our configuration and parameter setting is correct for indoor and outdoor hovering.

Thus, I have performed hand-held testing with optical flow and Lidar Lite indoor(not arming) based on EKF2, and record the flight log from boot until shutdown.

The following is the log from and-held testing.

EKF2_AID_MASK | 3
EKF2_HGT_MODE | 2

https://review.px4.io/plot_app?log=daf49809-eee3-4c90-ae22-75d78953978d

we would like to evaluate the EKF2 performance, for instance optical flow innovation, but python script does not work for this data.

It thinks that always on ground, always on ground and python scripts was not working.

kari@king:~/git/kari_ws/src/px4/Tools/ecl_ekf$ ./process_logdata_ekf.py /home/kari/Desktop/px4_log/log_0_no_flight_ekf2.ulg
found estimator_status data
found ekf2_innovation data
found sensor_preflight data
always on ground
always on ground
Traceback (most recent call last):
File "./process_logdata_ekf.py", line 778, in <module>
pp.savefig()
File "/usr/lib/python2.7/dist-packages/matplotlib/backends/backend_pdf.py", line 2483, in savefig
**kwargs)
File "/usr/lib/python2.7/dist-packages/matplotlib/figure.py", line 1565, in savefig
self.canvas.print_figure(*args, **kwargs)
File "/usr/lib/python2.7/dist-packages/matplotlib/backend_bases.py", line 2232, in print_figure
**kwargs)
File "/usr/lib/python2.7/dist-packages/matplotlib/backends/backend_pdf.py", line 2536, in print_pdf
self.figure.draw(renderer)
File "/usr/lib/python2.7/dist-packages/matplotlib/artist.py", line 61, in draw_wrapper
draw(artist, renderer, *args, **kwargs)
File "/usr/lib/python2.7/dist-packages/matplotlib/figure.py", line 1159, in draw
func(*args)
File "/usr/lib/python2.7/dist-packages/matplotlib/artist.py", line 61, in draw_wrapper
draw(artist, renderer, *args, **kwargs)
File "/usr/lib/python2.7/dist-packages/matplotlib/axes/_base.py", line 2324, in draw
a.draw(renderer)
File "/usr/lib/python2.7/dist-packages/matplotlib/artist.py", line 61, in draw_wrapper
draw(artist, renderer, *args, **kwargs)
File "/usr/lib/python2.7/dist-packages/matplotlib/text.py", line 757, in draw
raise ValueError("posx and posy should be finite values")
ValueError: posx and posy should be finite values

More specifically, I don't know why the value of pos_horiz_accuracy and pos_vert_accuracy is always zero. As fas as I know, proper EKF2 measurement update of optical flow and Lidar Lite was achieved, value of pos_horiz_accuracy and pos_vert_accuracy decreased.

pos_horiz_accuracy and pos_vert_accuracy is the standard deviation value of EKF2 horizontal(x, y), vertical(z states), and is the representation about how certain the states might be.

https://github.com/PX4/Firmware/blob/master/src/modules/commander/commander.cpp#L3075-L3076

As you can see above lines,

if (status_flags.condition_home_position_valid && status_flags.condition_global_position_valid) {
led_color = led_control_s::COLOR_GREEN;

https://docs.px4.io/en/flying/led_meanings.html
(We have external GPS with LED).

When pos_horiz_accuracy and pos_vert_accuracy is below the threshold(https://github.com/PX4/Firmware/blob/master/src/modules/commander/commander.cpp#L1123-L1124),
then status_flags.condition_home_position_valid = true(
https://github.com/PX4/Firmware/blob/master/src/modules/commander/commander.cpp#L1147)

and

In following lines(https://github.com/PX4/Firmware/blob/master/src/modules/commander/commander.cpp#L1997-L1998
https://github.com/PX4/Firmware/blob/master/src/modules/commander/commander.cpp#L3548),
check_posvel_validity PX4 firmware check also COM_HOME_H_T and COM_HOME_V_T params to understand the EPH and EPV thresholds used to accept the respective EPH and EPV published in the vehicle_global_position & vehicle_local_position msgs.

Then the above two conditions are met,

LED of GPS turn to be green, which means I can change to position_hold mode from stabilized mode.

From what I understand about the pos_horiz_accuracy and pos_vert_accuracy

When we used LPE instead of EKF2, we always saw that LED of GPS turn to be green indoor if optical flow measurement and LiDAR measurement was correct. And I was able to change into position_hold mode indoor successfully.

However, in EKF2
as you can see vehicle_local_position.eph & epv is zero, and pos_horiz_accuracy and pos_vert_accuracy is zero. It looks quite weired. If I see pos_horiz_accuracy and pos_vert_accuracy in analyser Tool in QGC, they were always zero as well, which does not makes sense to me.

In addition, It seems to me that status_flags.condition_home_position_valid is not set to be true indoor.
In LPE, when FAKE_ORIGIN was set to be true in indoor, status_flags.condition_home_position_valid is set to be true.

https://github.com/larics/px4-firmware/blob/master/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp#L393

By monitoring the green light of LED attached to UAV, I was confident that position mode will not be rejected in indoor, since pos_horiz_accuracy and pos_vert_accuracy is below the threshold, and home_position is valid.

Actually, there were someone who tried to add the functionality in EKF2 such as FAKE_Origin of LPE in order to perform automission indoor (http://discuss.px4.io/t/fake-origin-in-ekf2-for-indoor-vpe-mission/5069)

indoor!UNITO-UNDERSCORE!ekf2!UNITO-UNDERSCORE!hand!UNITO-UNDERSCORE!held

eph


To summarize,

My question is as follows:

  1. Do you think that hand-held testing indoor/outdoor help to make sure the our configuration and parameter setting is correct for indoor and outdoor hovering?

  2. Does this log look okay?

ekf2!UNITO-UNDERSCORE!optical flow

Optical flow innovation looks okay to me,

and down position innovation which is vel_pos_innov[5] looks good to me based on LiDAR Lite v3.

rng!UNITO-UNDERSCORE!innovation

local position2

local position

The value xy_valid does not look okay from times to times.

https://github.com/PX4/Firmware/blob/master/src/modules/ekf2/ekf2_main.cpp#L1034

https://github.com/PX4/ecl/blob/master/EKF/ekf_helper.cpp#L1259-L1268

The meaning that the value of xy_valid is zero is that we are totally reliant on inertial dead-reckoning for position, and that might be caused by sensor timeout for optical flow(Because I set to use optical flow indoor)

However, if you see the quality of optical flow, it was almost the maximum value(255) for the most of the time, and I don't know why time-out of optical flow measurement update occurred. That means that time between consecutive optical flow measurement is larger than update _params.no_aid_timeout_max(1s).

bool optFlowAiding = _control_status.flags.opt_flow && (_time_last_imu - _time_last_of_fuse <= _params.no_aid_timeout_max

  1. why the value of pos_horiz_accuracy and pos_vert_accuracy is always zero?

  2. It also looks strange that ulog from following link also shows that pos_horiz_accuracy and pos_vert_accuracy is always zero.

(https://github.com/priseborough/PX4-Firmware-private/issues/2)

https://github.com/PX4/Firmware/blob/master/msg/estimator_status.msg#L67-L68

float32 pos_horiz_accuracy # 1-Sigma estimated horizontal position accuracy relative to the estimators origin (m)
float32 pos_vert_accuracy # 1-Sigma estimated vertical position accuracy relative to the estimators origin (m)

Even if optical flow measurement update only provide LOS(Line of Sight) velocity measurement related Vn(Velocity for North direction), Vd(Velocity for Down direction), pos_horiz_accuracy and pos_vert_accuracy should be always decreased when the optical flow measurement update is performed correctly for EKF2.

More specifically, if we perform the observability analysis and analyse the rank of observability matrix , we will be able to conclude that we can deduce the information about the horizontal position and vertical position from the optical flow measurement.

Since optical flow innovation looks quite reasonable,
pos_horiz_accuracy and pos_vert_accuracy should not be zero all the time.

  1. we don't know why ./process_logdata_ekf.py python scripts is broken about this log. I guess that this python scripts was not designed to handle the this type of log such as hand-held testing.

However, do you think that python script will work if I arm the motor without propeller and perform hand-held testing?

Outdoor GPS/Optical Flow/Lidar Lite(Hand-held testing)

We have expensive device mounted on the UAV, and recently have experienced a few significant crash.

We would like to make sure that everything(UAV configuration & Sensor calibration & Parameter Setup) is okay for posCTRL mode and Auto Mode before real-flight.

This is the results of outdoor hand-held testing

GPS altitude of both log looks quite strange.

position_0.xy_valid & position_0.z_valid looks strange.

Optical flow innovation look okay, but not the optimal.

  1. https://review.px4.io/plot_app?log=6c3473c4-3d9c-4a2a-a748-0247d823f53f

  2. https://review.px4.io/plot_app?log=d49ccaaf-3b83-4ae9-a98d-72ab244a2f9c

This question has been quite a long, and would you please have a look at it?

@priseborough
Copy link
Contributor

Python script should work if you arm the motors (without propellers) , advance throttle to prevent disarm and do the hand carry test. Disarm to stop logging,

The commit hash indicates the OP generated these logs using v1.7.3 stable. I have had a look and the innovation sequences look OK. I have tried replaying the logs and unfortunately there are large dropouts of over 600mSec that prevent use of log replay as a diagnostics tool.

These look like they are the result of an SD card with large write time spikes relative to the amount of data that the PX4 logger can buffer.

Solutions to this are:

Using a better SD card - See https://dev.px4.io/en/log/logging.html . I use the SanDisk Extreme U3 32GB.
Increasing the buffer RAM allocation using the LOGGER_BUF parameter. You can use the nsh console to check the amount of free contiguous RAM.

@wkyoun
Copy link
Author

wkyoun commented Apr 1, 2018

@priseborough

Thank you for the cooperation,

and I have seen that pos_horiz_accuracy and pos_vert_accuracy was always zero even in QGC analyser during the test.

It also looks strange that ulog from following link also shows that pos_horiz_accuracy and pos_vert_accuracy is always zero.

  1. why the value of pos_horiz_accuracy and pos_vert_accuracy is always zero?

https://github.com/PX4/Firmware/blob/master/msg/estimator_status.msg#L67-L68

@wkyoun
Copy link
Author

wkyoun commented Apr 1, 2018

@priseborough


LOGGER_BUF

LOGGER_BUF cannot be found in https://dev.px4.io/en/advanced/parameter_reference.html
but found in https://github.com/PX4/Firmware/blob/master/ROMFS/px4fmu_common/init.d/rcS#L198 as the system start shell scripts.
Thus, LOGGER_BUF is not configurable in QGC.

As far as I understand, I need to create a file /fs/microsd/etc/rc.txt, which is located in the etc folder on the microSD card to increase LOGGER_BUF. In /fs/microsd/etc/rc.txt, I need to increase the value of LOGGER_BUF. Am I right?

Or is there any other easier way to change the LOGGER_BUF parameter?

In most cases customizing the default boot is the better approach, which is documented below. If the complete boot should be replaced, create a file /fs/microsd/etc/rc.txt, which is located in the etc folder on the microSD card. If this file is present nothing in the system will be auto-started.
(https://dev.px4.io/en/advanced/system_startup.html)


ulog for ekf2_innovations_s is missing in PX4FMU_V4

I(with different github id: dronecrewkari) recently made an issus as followings.
Please have a look at it.
(#9172)

This is not related to EKF2, but the reason why ulog for ekf2_innovations_s is missing in PX4FMU_V4 might be related to the LOGGER_BUF parameter.

or Do I need to specify the list of logged topics as explained here?
https://dev.px4.io/en/log/logging.html#Configuration

Actually, ulog topic of <ekf2_innovations_s> exists, but when I opened it, nothing is presented.
Except that, everything does match exactly as I expected

Do you have any thought about it?

@mhkabir
Copy link
Member

mhkabir commented Apr 1, 2018

You need a better SD card. Do not modify the logger buffer without knowing what you're doing and checking free RAM.

@wkyoun
Copy link
Author

wkyoun commented Apr 4, 2018

@mhkabir

Current SD card test

Sandisk edge 8GB MicrosSD(Class 5/UHS-I)

nsh> logger status
INFO  [logger] Running in mode: all
INFO  [logger] File Logging Running
INFO  [logger] Log file: /fs/microsd/log/sess004/log001.ulg
INFO  [logger] Wrote 3.43 MiB (avg 30.64 KiB/s)
INFO  [logger] Since last status: dropouts: 8 (max len: 0.258 s), max used buffer: 11060 / 14336 B

nsh> sd_bench -r 50
INFO  [sd_bench] Using block size = 4096 bytes, sync=0
INFO  [sd_bench] 
INFO  [sd_bench] Testing Sequential Write Speed...
INFO  [sd_bench]   Run  0:   331.15 KB/s, max write time: 25 ms (= 160.00 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run  1:   331.78 KB/s, max write time: 26 ms (= 153.85 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run  2:   264.55 KB/s, max write time: 351 ms (=  11.40 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run  3:   220.70 KB/s, max write time: 597 ms (=   6.70 KB/s), fsync: 7 ms
INFO  [sd_bench]   Run  4:   318.42 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run  5:   324.43 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run  6:   241.46 KB/s, max write time: 533 ms (=   7.50 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run  7:   332.33 KB/s, max write time: 26 ms (= 153.85 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run  8:   334.50 KB/s, max write time: 26 ms (= 153.85 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run  9:   181.20 KB/s, max write time: 539 ms (=   7.42 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 10:   325.65 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 7 ms
INFO  [sd_bench]   Run 11:   321.76 KB/s, max write time: 28 ms (= 142.86 KB/s), fsync: 7 ms
INFO  [sd_bench]   Run 12:   330.45 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run 13:   189.57 KB/s, max write time: 536 ms (=   7.46 KB/s), fsync: 785 ms
INFO  [sd_bench]   Run 14:   320.80 KB/s, max write time: 40 ms (= 100.00 KB/s), fsync: 12 ms
INFO  [sd_bench]   Run 15:   325.92 KB/s, max write time: 33 ms (= 121.21 KB/s), fsync: 7 ms
INFO  [sd_bench]   Run 16:   326.01 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 17:   147.62 KB/s, max write time: 1082 ms (=   3.70 KB/s), fsync: 40 ms
INFO  [sd_bench]   Run 18:   325.02 KB/s, max write time: 30 ms (= 133.33 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 19:   331.28 KB/s, max write time: 29 ms (= 137.93 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run 20:   328.77 KB/s, max write time: 23 ms (= 173.91 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 21:   171.03 KB/s, max write time: 755 ms (=   5.30 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run 22:   319.39 KB/s, max write time: 28 ms (= 142.86 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run 23:   325.55 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 24:   265.77 KB/s, max write time: 352 ms (=  11.36 KB/s), fsync: 7 ms
INFO  [sd_bench]   Run 25:   181.08 KB/s, max write time: 857 ms (=   4.67 KB/s), fsync: 7 ms
INFO  [sd_bench]   Run 26:   327.84 KB/s, max write time: 46 ms (=  86.96 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 27:   331.29 KB/s, max write time: 25 ms (= 160.00 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 28:   268.07 KB/s, max write time: 359 ms (=  11.14 KB/s), fsync: 14 ms
INFO  [sd_bench]   Run 29:   170.55 KB/s, max write time: 603 ms (=   6.63 KB/s), fsync: 7 ms
INFO  [sd_bench]   Run 30:   316.37 KB/s, max write time: 38 ms (= 105.26 KB/s), fsync: 8 ms
INFO  [sd_bench]   Run 31:   327.09 KB/s, max write time: 27 ms (= 148.15 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 32:   164.18 KB/s, max write time: 681 ms (=   5.87 KB/s), fsync: 30 ms
INFO  [sd_bench]   Run 33:   296.87 KB/s, max write time: 162 ms (=  24.69 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 34:   315.67 KB/s, max write time: 33 ms (= 121.21 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 35:   324.46 KB/s, max write time: 27 ms (= 148.15 KB/s), fsync: 7 ms
INFO  [sd_bench]   Run 36:   174.93 KB/s, max write time: 795 ms (=   5.03 KB/s), fsync: 28 ms
INFO  [sd_bench]   Run 37:   323.54 KB/s, max write time: 27 ms (= 148.15 KB/s), fsync: 11 ms
INFO  [sd_bench]   Run 38:   319.12 KB/s, max write time: 35 ms (= 114.29 KB/s), fsync: 19 ms
INFO  [sd_bench]   Run 39:   329.31 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 40:   165.62 KB/s, max write time: 679 ms (=   5.89 KB/s), fsync: 10 ms
INFO  [sd_bench]   Run 41:   329.90 KB/s, max write time: 26 ms (= 153.85 KB/s), fsync: 9 ms
INFO  [sd_bench]   Run 42:   319.70 KB/s, max write time: 28 ms (= 142.86 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 43:   252.31 KB/s, max write time: 374 ms (=  10.70 KB/s), fsync: 21 ms
INFO  [sd_bench]   Run 44:   260.77 KB/s, max write time: 416 ms (=   9.62 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run 45:   153.46 KB/s, max write time: 635 ms (=   6.30 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run 46:   321.86 KB/s, max write time: 33 ms (= 121.21 KB/s), fsync: 17 ms
INFO  [sd_bench]   Run 47:   335.15 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run 48:   230.07 KB/s, max write time: 552 ms (=   7.25 KB/s), fsync: 243 ms
INFO  [sd_bench]   Run 49:   322.71 KB/s, max write time: 28 ms (= 142.86 KB/s), fsync: 5 ms
INFO  [sd_bench]   Avg   :   278.94 KB/s

I have changed the SDcard as followings: SanDisk Extreme U3 32GB

nsh> logger status
INFO  [logger] Running in mode: all
INFO  [logger] File Logging Running
INFO  [logger] Log file: /fs/microsd/log/2018-04-04/06_28_26.ulg
INFO  [logger] Wrote 0.48 MiB (avg 32.52 KiB/s)
INFO  [logger] Since last status: dropouts: 2 (max len: 0.036 s), max used buffer: 7108 / 14336 B
nsh>  sd_bench -r 50
INFO  [sd_bench] Using block size = 4096 bytes, sync=0
INFO  [sd_bench] 
INFO  [sd_bench] Testing Sequential Write Speed...
INFO  [sd_bench]   Run  0:   391.54 KB/s, max write time: 26 ms (= 153.85 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run  1:   382.10 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run  2:   379.05 KB/s, max write time: 23 ms (= 173.91 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run  3:   386.34 KB/s, max write time: 29 ms (= 137.93 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run  4:   387.21 KB/s, max write time: 21 ms (= 190.48 KB/s), fsync: 8 ms
INFO  [sd_bench]   Run  5:   383.74 KB/s, max write time: 22 ms (= 181.82 KB/s), fsync: 8 ms
INFO  [sd_bench]   Run  6:   390.30 KB/s, max write time: 25 ms (= 160.00 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run  7:   378.03 KB/s, max write time: 22 ms (= 181.82 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run  8:   386.87 KB/s, max write time: 21 ms (= 190.48 KB/s), fsync: 8 ms
INFO  [sd_bench]   Run  9:   388.68 KB/s, max write time: 22 ms (= 181.82 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 10:   390.08 KB/s, max write time: 20 ms (= 200.00 KB/s), fsync: 3 ms
INFO  [sd_bench]   Run 11:   386.15 KB/s, max write time: 23 ms (= 173.91 KB/s), fsync: 3 ms
INFO  [sd_bench]   Run 12:   377.90 KB/s, max write time: 34 ms (= 117.65 KB/s), fsync: 8 ms
INFO  [sd_bench]   Run 13:   388.48 KB/s, max write time: 21 ms (= 190.48 KB/s), fsync: 3 ms
INFO  [sd_bench]   Run 14:   386.18 KB/s, max write time: 27 ms (= 148.15 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 15:   379.31 KB/s, max write time: 23 ms (= 173.91 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 16:   384.86 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 12 ms
INFO  [sd_bench]   Run 17:   385.74 KB/s, max write time: 22 ms (= 181.82 KB/s), fsync: 7 ms
INFO  [sd_bench]   Run 18:   380.48 KB/s, max write time: 22 ms (= 181.82 KB/s), fsync: 8 ms
INFO  [sd_bench]   Run 19:   383.40 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 20:   382.18 KB/s, max write time: 25 ms (= 160.00 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run 21:   392.67 KB/s, max write time: 23 ms (= 173.91 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 22:   376.84 KB/s, max write time: 23 ms (= 173.91 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 23:   385.32 KB/s, max write time: 27 ms (= 148.15 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run 24:   386.06 KB/s, max write time: 23 ms (= 173.91 KB/s), fsync: 3 ms
INFO  [sd_bench]   Run 25:   382.51 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run 26:   390.59 KB/s, max write time: 20 ms (= 200.00 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 27:   387.72 KB/s, max write time: 26 ms (= 153.85 KB/s), fsync: 3 ms
INFO  [sd_bench]   Run 28:   381.85 KB/s, max write time: 25 ms (= 160.00 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 29:   389.19 KB/s, max write time: 23 ms (= 173.91 KB/s), fsync: 8 ms
INFO  [sd_bench]   Run 30:   380.14 KB/s, max write time: 22 ms (= 181.82 KB/s), fsync: 7 ms
INFO  [sd_bench]   Run 31:   387.82 KB/s, max write time: 30 ms (= 133.33 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 32:   389.97 KB/s, max write time: 25 ms (= 160.00 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 33:   383.54 KB/s, max write time: 25 ms (= 160.00 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 34:   385.78 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 8 ms
INFO  [sd_bench]   Run 35:   380.20 KB/s, max write time: 22 ms (= 181.82 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 36:   385.91 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run 37:   387.33 KB/s, max write time: 26 ms (= 153.85 KB/s), fsync: 7 ms
INFO  [sd_bench]   Run 38:   386.09 KB/s, max write time: 22 ms (= 181.82 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run 39:   388.56 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 40:   382.92 KB/s, max write time: 26 ms (= 153.85 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 41:   384.38 KB/s, max write time: 21 ms (= 190.48 KB/s), fsync: 13 ms
INFO  [sd_bench]   Run 42:   388.35 KB/s, max write time: 34 ms (= 117.65 KB/s), fsync: 11 ms
INFO  [sd_bench]   Run 43:   388.26 KB/s, max write time: 21 ms (= 190.48 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 44:   388.64 KB/s, max write time: 23 ms (= 173.91 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 45:   387.08 KB/s, max write time: 22 ms (= 181.82 KB/s), fsync: 7 ms
INFO  [sd_bench]   Run 46:   380.52 KB/s, max write time: 24 ms (= 166.67 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run 47:   386.63 KB/s, max write time: 20 ms (= 200.00 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run 48:   388.36 KB/s, max write time: 26 ms (= 153.85 KB/s), fsync: 8 ms
INFO  [sd_bench]   Run 49:   394.18 KB/s, max write time: 22 ms (= 181.82 KB/s), fsync: 5 ms
INFO  [sd_bench]   Avg   :   385.52 KB/s

@priseborough
Copy link
Contributor

I found some potential issues in the way the EKF handles optical flow and external vision data resets - see PX4/PX4-ECL#418.

I will try to use your log as a test case.

@priseborough
Copy link
Contributor

Can you please provide a link to a log with optical flow data gathered using the new SD card so I can test it. TXS.

@wkyoun
Copy link
Author

wkyoun commented Apr 5, 2018

@priseborough

Do you mean the log such as the following link?

log: https://review.px4.io/plot_app?log=772e6920-b73a-4177-baf0-fb52a3076f0e
Parameter: https://review.px4.io/download?log=772e6920-b73a-4177-baf0-fb52a3076f0e&type=1

I found that the optical flow quality was not good, and EKF navigation failed

The problem I found is that

https://dev.px4.io/en/advanced/parameter_reference.html#CAL_MAG0_ROT

we used the external magnetometer of GPS, and

CAL_MAG0_ROT should be 0: No rotation, but was 2: Yaw 90° by mistake.
(since the direction of external magnetometer is aligned parallel with nose of the UAV)

After resetting CAL_MAG0_ROT to be 0: No rotation and recalibrating the sensor, everything look okay to me now as shown here.

https://logs.px4.io/plot_app?log=ca7c4321-5743-426d-ba68-fb60a1cea08a

log_12_2018-4-3-00-43-56.ulg.pdf

csv_file from above ulog: ekf_kari.tar.gz

I might be able to reproduce the aforementioned fault log by settting CAL_MAG0_ROT to 2: Yaw 90° if that's what you need.

Please let me know if you need the aforementioned fault log with no dropout(now we don't have dropout since we have changed the sd card as you mentioned)

@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

3 participants