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

Increase mpu6000/ mpu9250 rate and disable on-chip dlpf #7446

Closed
wants to merge 3 commits into from

Conversation

jgoppert
Copy link
Member

@jgoppert jgoppert commented Jun 20, 2017

Testing some ideas out from #7438 on pixhawk with mpu6000.

  • Gyro rate: 8 kHz
  • Accel rate: 1 kHz
  • No on-chip low pass filter

All of the integration that we discussed in #7438 is in place already so the low pass filters don't seem necessary. Also we can go full rate on the sensors without a noticeable increase in cpu. Since the data is logged at the same rate as the integrators, it should not be aliased and should be good for sysid.

@LorenzMeier
Copy link
Member

Can you share the output of top for reference?

@dagar dagar requested a review from davids5 June 20, 2017 13:39
@@ -204,12 +204,12 @@
#define MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ 30

#define MPU6000_GYRO_DEFAULT_RANGE_G 8
#define MPU6000_GYRO_DEFAULT_RATE 1000
#define MPU6000_GYRO_DEFAULT_RATE 8000
Copy link
Member

Choose a reason for hiding this comment

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

@jgoppert - I think we would need to instrument the 8K rate, My recollection from work I did on the icm20608 @ 4k - #3360 was that the device Access/Processing with interrupts off was 600+ uS out of 1000 uS. I did not decompose that into access and processing but I suspect that DMA is needed and the driver would need to be reworked to have a short (DMA)/long service (HP work processing)

Copy link
Member Author

@jgoppert jgoppert Jun 20, 2017

Choose a reason for hiding this comment

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

This is a bit above my head, but if the interrupt just fires faster than 280 Hz, the output rate. I'm OK. The FIFO buffer should handle all of the data and iterate through it integrating as it goes through the buffer, assuming the FIFO buffer is sufficiently large. Is there anything we need to do to configure the driver for that kind of sampling? Will this still have the issues you mention above?

Copy link
Member

Choose a reason for hiding this comment

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

@jgoppert

I would have to review the mpu6000 driver again, it has been a while and #3360is stale.

I would expect the same issues will exist in the mpu6000 devices as were seen with the icm20608 devices as it is the same driver.

Copy link
Member Author

@jgoppert jgoppert Jun 20, 2017

Choose a reason for hiding this comment

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

OK, what would the impact of this be. Is it basically dropping samples? Is there a way for me to check performance?

Copy link
Member

Choose a reason for hiding this comment

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

No, if it is really outputting samples at 8K, it is worse than that. The offload rate of the driver is still 1Khz. So the FIFO will be filling ~8 repeated accel samples and 8 gyro samples. The majority of the accel samples will be duplicates, but we have to read the FIFO or it will be over run. The time to off load the FIFO for the other part was ~600+Us out of 1000Us. In that time no other interrupts will be processed.

So all the interrupt driven IO (serial transmit, USB) performance will be impacted. Even the HRT will not provide reasonable scheduling and possibly improper time keeping. So top output may be may be unreliable.

Do you have a scope? Use the PROBE_INIT() and PROBE() macros to see the rate and duration of the MPU6000::measure_trampoline.

@jgoppert
Copy link
Member Author

jgoppert commented Jun 20, 2017

@LorenzMeier here is the comparison with top and status for mpu6000.

I've tested with the hk32pilot and an official pixhawk v1 and both results look similar to below, +/- 1 %.

master on hk32pilot32

Processes: 24 total, 2 running, 22 sleeping
CPU usage: 49.91% tasks, 1.34% sched, 48.75% idle
DMA Memory: 5120 total, 1024 used 1024 peak
Uptime: 66.478s total, 35.890s idle
 149 commander                    1261  2.049  2592/ 3652 140 (140)  w:sig 
 150 commander_low_prio              2  0.000   592/ 2996  50 ( 50)  w:sem 
 157 px4io                        1993  3.208  1048/ 1380 240 (240)  w:sem 
 171 mavlink_if0                  1035  1.604  1640/ 2436 100 (100)  w:sig 
 172 mavlink_rcv_if0               270  0.445  1504/ 2140 175 (175)  w:sem 
 184 mavlink_if1                   746  1.158  1640/ 2388 100 (100)  w:sig 
 185 mavlink_rcv_if1               270  0.356  1672/ 2140 175 (175)  w:sem 
 244 log_writer_file                 0  0.000   344/ 1060  60 ( 60)  w:sem 
 229 mavlink_if2                  3210  9.180  1720/ 2388 100 (100)  w:sig 
 230 mavlink_rcv_if2               271  0.445  1504/ 2140 175 (175)  w:sem 
 242 logger                        328  0.445  1272/ 3532 250 (250)  w:sem 
 346 top                            69  1.515  1288/ 1684 100 (100)  RUN   
 301 ekf2                         8249 13.458  5056/ 5780 250 (250)  w:sem 
 303 mc_att_control               2552  4.188  1176/ 1676 250 (250)  w:sem 
 305 mc_pos_control               1662  2.941   720/ 1876 250 (250)  w:sem 
 316 navigator                       7  0.000   784/ 1772 105 (105)  w:sem 

Processes: 24 total, 2 running, 22 sleeping
CPU usage: 49.91% tasks, 1.07% sched, 49.02% idle
DMA Memory: 5120 total, 1024 used 1024 peak
Uptime: 65.362s total, 35.344s idle

nsh> mpu6000 status
state @ 1000a6f0
mpu6k_read: 39356 events, 2039859us elapsed, 51us avg, min 32us max 75us 12.551us rms
mpu6k_acc_read: 1 events
mpu6k_gyro_read: 0 events
mpu6k_bad_trans: 0 events
mpu6k_bad_reg: 0 events
mpu6k_good_trans: 31471 events
mpu6k_reset: 0 events
mpu6k_duplicates: 7896 events
accel queue	2/144 (1/0 @ 10004650)
gyro queue	2/144 (0/2 @ 10007e60)
checked_next: 9
reg 11:00 should be 7e
temperature: 37.9

this branch with mpu6000 at 8 kHZ on hk32pilot32

 PID COMMAND                   CPU(ms) CPU(%)  USED/STACK PRIO(BASE) STATE 
   0 Idle Task                    7162 47.791   604/  748   0 (  0)  READY 
   1 hpwork                        488  3.886   888/ 1780 192 (192)  w:sig 
   2 lpwork                         38  0.353   640/ 1780  50 ( 50)  w:sig 
   3 init                        16592  0.000  1728/ 2484 100 (100)  w:sem 
 343 mavlink_shell                   0  0.000   872/ 2020 100 (100)  w:sem 
 100 gps                            36  0.618  1056/ 1524 220 (220)  w:sem 
 104 dataman                       152  0.000   704/ 1180  90 ( 90)  w:sem 
 147 sensors                       621  5.123  1464/ 1980 250 (250)  w:sem 
 149 commander                     259  2.031  2608/ 3652 140 (140)  w:sig 
 150 commander_low_prio              0  0.000   592/ 2996  50 ( 50)  w:sem 
 157 px4io                         386  3.356   976/ 1380 240 (240)  w:sem 
 171 mavlink_if0                   243  1.590  1656/ 2436 100 (100)  READY 
 172 mavlink_rcv_if0                51  0.353  1448/ 2140 175 (175)  w:sem 
 184 mavlink_if1                   203  1.148  1656/ 2388 100 (100)  w:sig 
 185 mavlink_rcv_if1                51  0.441  1552/ 2140 175 (175)  w:sem 
 244 log_writer_file                 0  0.000   344/ 1060  60 ( 60)  w:sem 
 229 mavlink_if2                   888  9.098  1656/ 2388 100 (100)  w:sig 
 230 mavlink_rcv_if2                55  0.441  1504/ 2140 175 (175)  w:sem 
 242 logger                         64  0.441  1272/ 3532 250 (250)  w:sem 
 346 top                            70  1.590  1288/ 1684 100 (100)  RUN   
 301 ekf2                         1372 13.515  5056/ 5780 250 (250)  w:sem 
 303 mc_att_control                424  3.975  1176/ 1676 250 (250)  w:sem 
 305 mc_pos_control                207  2.826   584/ 1876 250 (250)  w:sem 
 316 navigator                       3  0.000   904/ 1772 105 (105)  w:sem 

Processes: 24 total, 3 running, 21 sleeping
CPU usage: 50.80% tasks, 1.41% sched, 47.79% idle
DMA Memory: 5120 total, 1024 used 1024 peak
Uptime: 14.248s total, 7.163s idle

nsh> mpu6000 status
state @ 1000a6f0
mpu6k_read: 86638 events, 4461015us elapsed, 51us avg, min 32us max 74us 12.125us rms
mpu6k_acc_read: 5 events
mpu6k_gyro_read: 0 events
mpu6k_bad_trans: 0 events
mpu6k_bad_reg: 0 events
mpu6k_good_trans: 69309 events
mpu6k_reset: 0 events
mpu6k_duplicates: 17343 events
accel queue	2/144 (1/0 @ 10004650)
gyro queue	2/144 (1/0 @ 10007e60)
checked_next: 3
reg 11:00 should be 7e
temperature: 35.6

@jgoppert
Copy link
Member Author

jgoppert commented Jun 20, 2017

I just need a sanity check here to make sure it is actually setting the sampling rate to 8 kHz. It is a bit confusing, but from the table in the manual I believe we are setting all the registers correctly.

https://github.com/PX4/Firmware/blob/master/src/drivers/mpu6000/mpu6000.cpp#L916

image

We are using CLK_SEL = 3, SAMPLERATE_DIV = 0 DLPFCFG = 0 with the new settings, from looking at what we write to the registers.

Independent of the sampling rate, it still would be worth validating that the on-chip dlpf can be disabled, so will try a flight.

@LorenzMeier
Copy link
Member

@jgoppert Let us know what you find. @MaEtUgR Please watch / follow this closely. This is the first and most important step for the rate loop audit.

@jgoppert
Copy link
Member Author

After having a call with @davids5 he has convinced me that the FIFO isn't running and that we are effectively dropping the extra samples. In order to get the FIFO working it sounds like we will have to figure out DMA for the imu drivers.

@jgoppert jgoppert force-pushed the imu_sampling branch 2 times, most recently from 7a3c3dc to 773149a Compare June 29, 2017 07:01
@jgoppert
Copy link
Member Author

jgoppert commented Jun 29, 2017

@LorenzMeier @davids5 @MaEtUgR @priseborough I got this working . I split the the accel and gyro reports so they can now run at separate rates. So we are running the integrators at the full sampling rate of the imu without any lowpass filter.

I added perf interval objects to confirm the sampling rate.

mpu6k_sample_interval_accel: 11649 events, 1002us avg, min 751us max 2111us 66.437us rms
mpu6k_sample_interval_gyro: 93483 events, 124us avg, min 49us max 230us 19.370us rms
mpu6k_read: 93515 events, 4401379us elapsed, 47us avg, min 44us max 78us 4.868us rms
mpu6k_acc_read: 6 events
mpu6k_gyro_read: 0 events
mpu6k_bad_trans: 0 events
mpu6k_bad_reg: 0 events
mpu6k_good_trans: 93693 events
mpu6k_reset: 0 events
mpu6k_duplicates: 0 events
accel queue	2/144 (1/0 @ 10004590)
gyro queue	2/144 (2/1 @ 10007650)
checked_next: 5
temperature: 41.9
nsh> mpu6000 test
WARN  [mpu6000] single read
WARN  [mpu6000] time:     23988206
WARN  [mpu6000] acc  x:  	  0.3376	m/s^2
WARN  [mpu6000] acc  y:  	 -0.4735	m/s^2
WARN  [mpu6000] acc  z:  	 -9.7892	m/s^2
WARN  [mpu6000] acc  x:  	111	raw 0x6f
WARN  [mpu6000] acc  y:  	-310	raw 0xfeca
WARN  [mpu6000] acc  z:  	-4535	raw 0xee49
WARN  [mpu6000] acc range:  78.4532 m/s^2 (  8.0000 g)
WARN  [mpu6000] gyro x: 	  0.00170	rad/s
WARN  [mpu6000] gyro y: 	  0.00077	rad/s
WARN  [mpu6000] gyro z: 	 -0.00169	rad/s
WARN  [mpu6000] gyro x: 	31	raw
WARN  [mpu6000] gyro y: 	69	raw
WARN  [mpu6000] gyro z: 	11	raw
WARN  [mpu6000] gyro range:  34.9066 rad/s (2000 deg/s)
WARN  [mpu6000] temp:  	 42.0249	deg celsius
WARN  [mpu6000] temp:  	2536	raw 0x9e8
nsh> 

@LorenzMeier
Copy link
Member

Cool - what is the CPU load with this?

@jgoppert
Copy link
Member Author

jgoppert commented Jun 29, 2017

CPU definitely went up now, so we will probably still need the FIFO as @davids5 suggested. This is on an hk32 pilot and an mpu6000.

Any idea why ekf2 load is now doubled? I'm publishing at the correct rate, so it must just be the interrupt on the spi I'm guessing.

 PID COMMAND                   CPU(ms) CPU(%)  USED/STACK PRIO(BASE) STATE 
   0 Idle Task                   50237 12.150   460/  748   0 (  0)  READY 
   1 hpwork                      16188  5.817   992/ 1780 192 (192)  w:sig 
   2 lpwork                       1070  0.368   640/ 1780  50 ( 50)  w:sig 
   3 init                         4320  0.000  1680/ 2484 100 (100)  w:sem 
 345 mavlink_shell                   1  0.000   904/ 2020 100 (100)  w:sem 
  95 gps                          1007  0.662  1064/ 1524 220 (220)  w:sig 
 145 sensors                     26243  9.425  1464/ 1980 250 (250)  w:sem 
 147 commander                    9881  3.534  2632/ 3652 140 (140)  w:sig 
 148 commander_low_prio             15  0.000   648/ 2996  50 ( 50)  w:sem 
 155 px4io                       13250  4.786   952/ 1380 240 (240)  w:sem 
 168 mavlink_if0                  7895  2.577  1736/ 2436 100 (100)  READY 
 169 mavlink_rcv_if0              1979  0.662  1624/ 2140 175 (175)  w:sem 
 181 mavlink_if1                  5857  1.988  1736/ 2388 100 (100)  w:sig 
 182 mavlink_rcv_if1              2018  0.662  1520/ 2140 175 (175)  w:sem 
 346 top                           163  0.000  1288/ 1684 100 (100)  w:sem 
 220 mavlink_if2                 31265 14.064  1736/ 2388 100 (100)  READY 
 221 mavlink_rcv_if2              2117  0.810  1528/ 2140 175 (175)  w:sem 
 237 logger                       2205  0.736  1192/ 3532 250 (250)  w:sem 
 238 log_writer_file                 0  0.000   344/ 1060  60 ( 60)  w:sem 
 292 ekf2                        68889 24.668  5056/ 5780 250 (250)  w:sem 
 294 mc_att_control              21767  7.879  1176/ 1676 250 (250)  w:sem 
 298 mc_pos_control              13805  5.007   720/ 1876 250 (250)  w:sem 
 303 navigator                      40  0.000   888/ 1772 105 (105)  w:sem 
 350 mavlink_shell                   1  0.000   904/ 2020 100 (100)  w:sem 
 357 top                           244  2.577  1296/ 1684 100 (100)  RUN   

Processes: 25 total, 4 running, 21 sleeping
CPU usage: 86.23% tasks, 1.62% sched, 12.15% idle
DMA Memory: 5120 total, 0 used 0 peak
Uptime: 280.407s total, 50.238s idle

@nicolaerosia
Copy link
Contributor

@jgoppert have you also enabled the mag? I can't get 8 KHz sampling rate with mag enabled, only somewhere around 7.36 KHz, FIFO doesn't seem to publish at that rate. If I disable the mag, the FIFO seems to work as expected.

@nicolaerosia
Copy link
Contributor

@jgoppert the accel runs at 4 KHz, so it makes sense to skip a sample every 2 samples instead of processing & integrating it.

@mhkabir
Copy link
Member

mhkabir commented Jun 29, 2017

@nicolaerosia I believe that the MPU6000 can only do 1kHz accel sampling, not 4kHz like the 9250. It also doesn't have a magnetometer.

@nicolaerosia
Copy link
Contributor

@mhkabir oh, thought this was the mpu9250, you're right.

@jgoppert
Copy link
Member Author

jgoppert commented Jun 29, 2017

Yes, focusing on mpu6000 here. It seems the cpu load is from running the interrupt routine at 8 kHz. I can run it at 2 kHz without any noticeable load increase, and run it at 4 kHz, with cpu load at 60% instead of 50%. At 2 kHz the data is still coming in at 8 kHz and I'm just grabbing the last packet I believe. So if that interpretation is correct, this is actually a pretty decent approach. Also, newer chips could bump it up to 8 kHz. We are definitely dropping packets above 1kHz and below 8 kHz, but it is better than enabling the dlpf on the chip, which drops the sampling rate to 1 kHz.

nsh> top


 PID COMMAND                   CPU(ms) CPU(%)  USED/STACK PRIO(BASE) STATE 
   0 Idle Task                   11099 47.810   460/  748   0 (  0)  READY 
   1 hpwork                        791  3.574   816/ 1780 192 (192)  w:sig 
   2 lpwork                         81  0.357   640/ 1780  50 ( 50)  w:sig 
   3 init                         4638  0.000  1672/ 2484 100 (100)  w:sem 
 345 mavlink_shell                   0  0.000   872/ 2020 100 (100)  w:sem 
  95 gps                            56  0.000  1024/ 1524 220 (220)  w:sig 
 145 sensors                      1128  4.825  1464/ 1980 250 (250)  w:sem 
 147 commander                     461  2.055  2632/ 3652 140 (140)  w:sig 
 148 commander_low_prio              0  0.000   592/ 2996  50 ( 50)  w:sem 
 155 px4io                         639  3.038   968/ 1380 240 (240)  w:sem 
 168 mavlink_if0                   371  1.608  1720/ 2436 100 (100)  w:sig 
 169 mavlink_rcv_if0                88  0.357  1648/ 2140 175 (175)  w:sem 
 181 mavlink_if1                   274  1.251  1656/ 2388 100 (100)  w:sig 
 182 mavlink_rcv_if1                88  0.446  1504/ 2140 175 (175)  w:sem 
 346 top                           105  1.519  1288/ 1684 100 (100)  RUN   
 220 mavlink_if2                  1697  9.383  1720/ 2388 100 (100)  w:sig 
 221 mavlink_rcv_if2                93  0.446  1448/ 2140 175 (175)  w:sem 
 237 logger                        104  0.446  1184/ 3532 250 (250)  w:sem 
 238 log_writer_file                 0  0.000   344/ 1060  60 ( 60)  w:sem 
 292 ekf2                         2783 15.281  5056/ 5780 250 (250)  w:sem 
 294 mc_att_control                797  3.932  1176/ 1676 250 (250)  w:sem 
 298 mc_pos_control                407  2.502   632/ 1876 250 (250)  w:sem 
 303 navigator                       4  0.000   824/ 1772 105 (105)  w:sem 

Processes: 23 total, 2 running, 21 sleeping
CPU usage: 51.03% tasks, 1.16% sched, 47.81% idle
DMA Memory: 5120 total, 0 used 0 peak
Uptime: 22.632s total, 11.099s idle

mpu6k_sample_interval_accel: 202256 events, 1002us avg, min 434us max 3037us 83.743us rms
mpu6k_sample_interval_gyro: 405440 events, 499us avg, min 387us max 613us 21.476us rms
mpu6k_read: 405451 events, 21306271us elapsed, 52us avg, min 44us max 77us 7.696us rms
mpu6k_acc_read: 8 events
mpu6k_gyro_read: 0 events
mpu6k_bad_trans: 0 events
mpu6k_bad_reg: 0 events
mpu6k_good_trans: 405475 events
mpu6k_reset: 0 events
mpu6k_duplicates: 203202 events
accel queue	2/144 (0/2 @ 10004590)
gyro queue	2/144 (0/2 @ 10007650)
checked_next: 2
temperature: 42.2
nsh> mpu6000 test
WARN  [mpu6000] single read
WARN  [mpu6000] time:     211632713
WARN  [mpu6000] acc  x:  	  0.0573	m/s^2
WARN  [mpu6000] acc  y:  	 -0.7893	m/s^2
WARN  [mpu6000] acc  z:  	 -9.7814	m/s^2
WARN  [mpu6000] acc  x:  	2	raw 0x2
WARN  [mpu6000] acc  y:  	-445	raw 0xfe43
WARN  [mpu6000] acc  z:  	-4514	raw 0xee5e
WARN  [mpu6000] acc range:  78.4532 m/s^2 (  8.0000 g)
WARN  [mpu6000] gyro x: 	 -0.00060	rad/s
WARN  [mpu6000] gyro y: 	  0.00007	rad/s
WARN  [mpu6000] gyro z: 	 -0.00287	rad/s
WARN  [mpu6000] gyro x: 	30	raw
WARN  [mpu6000] gyro y: 	68	raw
WARN  [mpu6000] gyro z: 	11	raw
WARN  [mpu6000] gyro range:  34.9066 rad/s (2000 deg/s)
WARN  [mpu6000] temp:  	 42.2465	deg celsius
WARN  [mpu6000] temp:  	2616	raw 0xa38
nsh> 

@jgoppert jgoppert force-pushed the imu_sampling branch 2 times, most recently from 9c74ec5 to de35a38 Compare June 29, 2017 08:41
@jgoppert jgoppert changed the title WIP: Increase mpu6000 rate to max and disable on-chip dlpf WIP: Increase mpu6000 rate and disable on-chip dlpf Jun 29, 2017
@jgoppert
Copy link
Member Author

jgoppert commented Jun 29, 2017

@nicolaerosia What was your cpu load like at 8 kHz with the mpu9250 on linux?

@jgoppert
Copy link
Member Author

If this looks good, I can also make the same changes to the mpu9250 driver for nuttx. Let me know if this would be worth doing and how it fits in to your work @nicolaerosia. I think we were both thinking along the same lines with separating the pubs.

@jgoppert
Copy link
Member Author

jgoppert commented Jun 29, 2017

I ported it to the mpu9250, wasn't too hard:

Using port /dev/serial/by-id/usb-3D_Robotics_PX4_FMU_v4.x_PRO_0-if00
Connecting to MAVLINK...

NuttShell (NSH)
nsh> 
nsh> 
nsh> top
 PID COMMAND                   CPU(ms) CPU(%)  USED/STACK PRIO(BASE) STATE 
   0 Idle Task                   19040 43.902   468/  748   0 (  0)  READY 
   1 hpwork                       1569  4.268   904/ 1780 192 (192)  w:sig 
   2 lpwork                        123  0.348   640/ 1780  50 ( 50)  w:sig 
   3 init                         8281  0.000  1784/ 2484 100 (100)  w:sem 
 237 log_writer_file                 0  0.000   344/ 1060  60 ( 60)  w:sem 
 103 gps                           170  0.522  1064/ 1524 220 (220)  w:sig 
 107 dataman                       130  0.000   704/ 1180  90 ( 90)  w:sem 
 144 sensors                      2114  5.574  1464/ 1980 250 (250)  w:sem 
 146 commander                     821  2.090  2792/ 3652 140 (140)  w:sig 
 153 px4io                        1200  3.222   896/ 1380 240 (240)  w:sem 
 165 mavlink_if0                   669  1.742  1656/ 2436 100 (100)  w:sig 
 166 mavlink_rcv_if0               166  0.522  1448/ 2140 175 (175)  w:sem 
 179 mavlink_if1                   527  1.393  1648/ 2388 100 (100)  w:sig 
 180 mavlink_rcv_if1               169  0.435  1696/ 2140 175 (175)  w:sem 
 216 mavlink_if2                  3187 10.191  1720/ 2388 100 (100)  w:sig 
 218 mavlink_rcv_if2               180  0.609  1448/ 2140 175 (175)  w:sem 
 234 logger                        200  0.435  1272/ 3532 250 (250)  w:sem 
 315 commander_low_prio              1  0.000   728/ 2996  50 ( 50)  w:sem 
 279 ekf2                         5538 15.243  5056/ 5780 250 (250)  w:sem 
 284 mc_att_control               1467  4.181  1176/ 1676 250 (250)  w:sem 
 286 mc_pos_control                815  2.526   744/ 1876 250 (250)  w:sem 
 296 navigator                       6  0.000   824/ 1772 105 (105)  w:sem 
 317 mavlink_shell                   0  0.000   840/ 2020 100 (100)  w:sem 
 319 top                           172  0.000  1320/ 1684 100 (100)  w:sem 
 329 mavlink_shell                   0  0.000   840/ 2020 100 (100)  w:sem 
 332 top                           155  2.090  1288/ 1684 100 (100)  RUN   

Processes: 26 total, 2 running, 24 sleeping
CPU usage: 55.40% tasks, 0.70% sched, 43.90% idle
DMA Memory: 5120 total, 1024 used 1024 peak
Uptime: 40.177s total, 19.041s idle
nsh> mpu9250 info
state @ 1000ab60
mpu6k_sample_interval_accel: 45089 events, 1038us avg, min 488us max 3924us 224.565us rms
mpu6k_sample_interval_gyro: 95598 events, 489us avg, min 362us max 572us 20.186us rms
mpu9250_read: 95604 events, 7378971us elapsed, 77us avg, min 71us max 95us 5.647us rms
mpu9250_acc_read: 7 events
mpu9250_gyro_read: 0 events
mpu9250_bad_trans: 0 events
mpu9250_bad_reg: 0 events
mpu9250_good_trans: 95630 events
mpu9250_reset: 0 events
mpu9250_dupe: 50525 events
accel queue	2/144 (1/0 @ 1000b1c0)
gyro queue	2/144 (2/1 @ 1000b2c0)
mag queue	2/112 (2/1 @ 1000b450)
checked_next: 7
temperature: 57.3
nsh> 
WARN  [mpu9250] single read
WARN  [mpu9250] time:     146729395
WARN  [mpu9250] acc  x:  	 -1.0721	m/s^2
WARN  [mpu9250] acc  y:  	 -0.6573	m/s^2
WARN  [mpu9250] acc  z:  	 -9.8956	m/s^2
WARN  [mpu9250] acc  x:  	-118	raw 0xff8a
WARN  [mpu9250] acc  y:  	245	raw 0xf5
WARN  [mpu9250] acc  z:  	-2143	raw 0xf7a1
WARN  [mpu9250] acc range: 156.9064 m/s^2 ( 16.0000 g)
WARN  [mpu9250] gyro x: 	  0.00235	rad/s
WARN  [mpu9250] gyro y: 	  0.00573	rad/s
WARN  [mpu9250] gyro z: 	 -0.00465	rad/s
WARN  [mpu9250] gyro x: 	-12	raw
WARN  [mpu9250] gyro y: 	0	raw
WARN  [mpu9250] gyro z: 	2	raw
WARN  [mpu9250] gyro range:  34.9066 rad/s (2000 deg/s)
WARN  [mpu9250] temp:  	 59.8504	deg celsius
WARN  [mpu9250] temp:  	8971	raw 0x230b
WARN  [mpu9250] mag x: 	 -0.06748	rad/s
WARN  [mpu9250] mag y: 	 -0.11671	rad/s
WARN  [mpu9250] mag z: 	  0.52318	rad/s
WARN  [mpu9250] mag x: 	-45	raw
WARN  [mpu9250] mag y: 	-87	raw
WARN  [mpu9250] mag z: 	367	raw
WARN  [mpu9250] mag range:  48.0000 Ga
WARN  [mpu9250] mag temp:   59.8670	deg celsius

@jgoppert jgoppert changed the title WIP: Increase mpu6000 rate and disable on-chip dlpf WIP: Increase mpu6000/ mpu9250 rate and disable on-chip dlpf Jun 29, 2017
@mhkabir
Copy link
Member

mhkabir commented Jun 29, 2017

How different are the 6000 and 9250? Any possibility to merge the drivers into a generic Invensense driver ?

@jgoppert
Copy link
Member Author

Definitely a lot of repeated code sections, but would take awhile, we have a lot of random ifdefs stuck in here and there that don't match between drivers.

@jgoppert
Copy link
Member Author

Flight test with iris and 2 kHz mpu6000: http://review.px4.io/plot_app?log=3a944623-df11-4fe2-85e8-8b35776b7419

@jgoppert jgoppert changed the title WIP: Increase mpu6000/ mpu9250 rate and disable on-chip dlpf Increase mpu6000/ mpu9250 rate and disable on-chip dlpf Jun 29, 2017
@nicolaerosia
Copy link
Contributor

@jgoppert the load was light ~ 30%.
Could you please test 8 KHz for gyro, 4 KHz accel, 100 Hz for mag, and show the sample interval for mag too?
My comment regarding integration still applies:
"the accel runs at 4 KHz, so it makes sense to skip a sample every 2 samples instead of processing & integrating it."
In your case (first post) you're saying that gyro runs at 8 KHz and accel at 1 KHz

@jgoppert
Copy link
Member Author

jgoppert commented Jun 29, 2017

@nicolaerosia I'm currently running the gyro at 2 kHz and the accel at 1 kHZ. At 8 kHz we have ~90% cpu load, so can't test those rates on nuttx currently. For the repeated accel values the code just checks for duplicates and ignores them. So the integration does happen at the proper rate for the accel already. The rate I'm logging is at the same spot where the integration step occurs.

Adding the mag sample rate is a good idea. Will do that.

@nicolaerosia
Copy link
Contributor

@jgoppert I noticed that checking for duplicates might not be the best solution, I often get duplicates when the drone is not moving at all.

@jgoppert
Copy link
Member Author

jgoppert commented Jun 29, 2017

@nicolaerosia That is what has been running on nuttx, so I didn't want to make a huge change, but I also wondered how effective that is, and tried a timestamp based method. The only issue was that the mean sampling team was hard to pin down then. If the gyro rate is a multiple of the accel rate I do think your approach is best. So I could run the gyro at 2kHz and the accel at 1 kHz as I am doing and just use modulo on the count.

@jgoppert
Copy link
Member Author

jgoppert commented Jul 1, 2017

@LorenzMeier worth sending this to the flight test team?

@jgoppert
Copy link
Member Author

jgoppert commented Jul 9, 2017

@davids5 @nicolaerosia Any chance you can do a review here so we can get this merged. @LorenzMeier is anyone able to fly this on your side? @nicolaerosia I think changing how the sampling works for accel can be done later, I'm trying to make the minimal amount of changes to just get the increased sampling rate in.

@lamping7
Copy link
Member

lamping7 commented Oct 26, 2017

What's the status on this? I'm trying to use @jgoppert sysid code here https://github.com/dronecrew/ulog_tools

With a Pixhawk 2.1 his script is telling me that my data is only 9Hz, which I find odd considering the default rate of 280. https://review.px4.io/download?log=477be5e0-4491-442d-a0f6-f7ed1433c83c

I bypassed his frequency check and got this dronecrew/ulog_tools#4. I'm hoping it is due to the sample rate.

EDIT: Solved by changing SDLOG param.

@LorenzMeier
Copy link
Member

@priseborough Could you review this so we can see where to take this? Generally I'd love to clean up the sensor architecture Q1/2018 so we're completely happy with it.

@dagar
Copy link
Member

dagar commented Dec 30, 2017

This could be okay for a small increase short term, but SPI DMA is almost certainly the way we want to go longer term for 8kHz or faster.

@priseborough
Copy link
Contributor

priseborough commented Jan 1, 2018

This moves us in the right direction in terms of splitting inertial navigation and control feedback signal processing paths. The higher level goals from my perspective are:

  • Separate the signal processing chains for autopilot control feedback and inertial navigation so we can use the most appropriate filtering and downsampling technique for each. Inertial navigation is best served by doing high rate integration on the raw data data. For autopilot control feedback, we want to filter motor/prop vibration to acceptable levels with minimal added phase/group delay.

  • Expose the raw sensor measurements so that clipping can be detected reliably. This is a significant pain point for many system integrators.

  • Expose the raw sensor measurements so that in the future we have the option of adding a special raw data logging mode that can be used to do spectral analysis of vehicle vibration to help with isolation mount design and trouble shooting. This is a significant pain point for many system integrators.

  • Enable high rate reading at 4kHz or higher with SPI bus sensors so that high rate sampling can be used to reduce vulnerability to aliasing effects. Requires use of SPI DMA with FIFO.

@dagar
Copy link
Member

dagar commented Oct 3, 2018

Closing this PR, but keeping the branch for now.
New effort (with SPI DMA) in #10602

@dagar dagar closed this Oct 3, 2018
@LorenzMeier LorenzMeier deleted the imu_sampling branch January 21, 2019 10:46
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.

9 participants