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

NuttX stm32f7 re-enable dcache with write back #12435

Merged
merged 2 commits into from
Jul 10, 2019
Merged

NuttX stm32f7 re-enable dcache with write back #12435

merged 2 commits into from
Jul 10, 2019

Conversation

dagar
Copy link
Member

@dagar dagar commented Jul 8, 2019

WIP PR for testing NuttX dcache writeback fixes on Jenkins HIL.

@dagar dagar force-pushed the pr-f7_dcache branch 3 times, most recently from a22a3f8 to ddbc38c Compare July 9, 2019 01:51
@dagar
Copy link
Member Author

dagar commented Jul 9, 2019

@davids5 this is working with the NuttX 7.29 update (#12344). I believe the difference is the cache unification. https://groups.google.com/forum/#!searchin/nuttx/cache$20unify%7Csort:date/nuttx/fGAD89gI6-M/8TV_RLWjCQAJ

PX4/NuttX@64252a2#diff-2f27829e583fd2f028175d1d9709a719

@dagar dagar requested a review from davids5 July 9, 2019 01:54
@dagar dagar changed the title [WIP]: F7 dcache writeback NuttX stm32f7 re-enable dcache without writeback Jul 9, 2019
@dagar dagar marked this pull request as ready for review July 9, 2019 01:55
@dagar dagar requested a review from a team July 9, 2019 01:55
@dagar
Copy link
Member Author

dagar commented Jul 9, 2019

@PX4/testflights could you try this on all fmu-v5 hardware (pixhawk 4, 4 mini, cuav 5+ and 5 nano)?

@dagar dagar changed the title NuttX stm32f7 re-enable dcache without writeback NuttX stm32f7 re-enable dcache with write back Jul 9, 2019
@dagar dagar force-pushed the pr-f7_dcache branch 2 times, most recently from a00f3d3 to fae6a8a Compare July 9, 2019 02:34
Copy link
Member

@davids5 davids5 left a comment

Choose a reason for hiding this comment

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

Last we tested this the PIO changes alone did not fix the issues. Was part of the fix in 7.29?

@dannyfpv
Copy link

dannyfpv commented Jul 9, 2019

Tested on Pixhawk4 v5 f-450
Modes Tested: 

Position Mode: no issue 
Altitude Mode: no issue 
Stabilized Mode: no issue 
mission mode : no issues
PR log:
https://review.px4.io/plot_app?log=c6b26152-f3ad-4b96-a9ff-df5b38dea367

Master log:
https://review.px4.io/plot_app?log=875cb2b2-79d5-4953-b13b-69fe9dba9c9e

@dagar we will test the CUAV 5+ tomorrow, we have the set up ready.

@Junkim3DR
Copy link

Tested on Pixhawk 4mini v5:

Modes Tested:
Position Mode: Good.
Altitude Mode: Good.
Stabilized Mode: Good.
Mission Plan Mode (Automated): Good.
RTL: Good.

Procedure:
Arm and Take off in position mode, after flying for approximately one minute, switched to altitude then stabilized mode proceed to switch to mission plan mode then make sure that vehicle follows all waypoints as shown in QGC, once completed all waypoint activate RTL and see landing behaviour.

Notes:
No issues noted, good flight in general.

Logs:

Tested on Pixhawk Pro v4:

Modes Tested:

  • Position Mode: Good.
  • Altitude Mode: Good.
  • Stabilized Mode: Good.
  • Mission Plan Mode (Automated): Good.
  • RTL: Good.

Procedure:
Arm and Take off in position mode, after flying for approximately one minute, switched to altitude then stabilized mode proceed to switch to mission plan mode then make sure that vehicle follows all waypoints as shown in QGC, once completed all waypoint activate RTL and see landing behaviour.

Notes:
No issues noted, good flight in general.

Logs:

Tested on NXP FMUK66 v3:

Modes Tested:

  • Position Mode: Good.
  • Altitude Mode: Good.
  • Stabilized Mode: Good.
  • Mission Plan Mode (Automated): Good.
  • RTL: Good.

Procedure:
Arm and Take off in position mode, after flying for approximately one minute, switched to altitude then stabilized mode proceed to switch to mission plan mode then make sure that vehicle follows all waypoints as shown in QGC, once completed all waypoint activate RTL and see landing behaviour.

Notes:
No issues noted, good flight in general.

Logs:

@jorge789
Copy link

jorge789 commented Jul 10, 2019

Tested on Pixhack v5+:

Modes Tested:
Position Mode: Good.
Altitude Mode: Good.
Stabilized Mode: Good.
Mission Plan Mode (Automated): Good.
RTL: Good.

Procedure:
Arm and Take off in position mode, after flying for approximately one minute, switched to altitude then stabilized mode proceed to switch to mission plan mode then make sure that vehicle follows all waypoints as shown in QGC, once completed all waypoint activate RTL and see landing behaviour.

Notes:
No issues noted, good flight in general.

Logs:
https://review.px4.io/plot_app?log=9c882101-d3b6-4561-88d8-cbb237ee0385

@davids5
Copy link
Member

davids5 commented Jul 10, 2019

Last we tested this the PIO changes alone did not fix the issues. Was part of the fix in 7.29?

@dagar OK I understand it now:

The dcache is a 4 way assoc cache it has 128 indexes * 4 ways == 512 entries * 32 byte line size == 16KB cache.

The nuttx 7.28 code arch_invalidate_dcache was purely wrong: taking an address and making a set is fine but invalidating all 4 ways is incorrect. It should have invalidated just one. But that is not how it is supposed to be done. The correct way to do it is using the MVA (DCCMVAC -Data cache clean by address to the PoCb) as it is in 7.29

This did not matter in a Write Through scheme because what was written in the cache was (also) in memory. An invalidate operation would lead to a later read it back. But in write back mode the invalidate lost the data not yet committed to memory.

Adding this to master proves the point by fixing the bad code.

tmpways = 3..0

      do
         {
           sw = ((tmpways << wshift) | (set << sshift));

+           putreg32(sw, NVIC_DCCSW); // Clean (commit to memory dirty entries) all the ways of a set 
+           ARM_DSB();
           putreg32(sw, NVIC_DCISW);
         }
       while (tmpways--);

Works.

@davids5 davids5 self-requested a review July 10, 2019 21:26
davids5
davids5 previously approved these changes Jul 10, 2019
Copy link
Member

@davids5 davids5 left a comment

Choose a reason for hiding this comment

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

@dagar - Good to go once rebased.

@davids5
Copy link
Member

davids5 commented Jul 10, 2019

@dagar rebased on master and force pushed.

@dagar
Copy link
Member Author

dagar commented Jul 10, 2019

Thank you @davids5!

@davids5
Copy link
Member

davids5 commented Jul 10, 2019

Just some metrics:
This PR with Write Back D:

 PID COMMAND                   CPU(ms) CPU(%)  USED/STACK PRIO(BASE) STATE FD
   0 Idle Task                   23070 59.287   284/  748   0 (  0)  READY  3
   1 hpwork                          0  0.000   344/ 1780 249 (249)  w:sig  3
   2 lpwork                         18  0.084   608/ 1780  50 ( 50)  w:sig  8
   3 init                          826  0.000  1728/ 2604 100 (100)  w:sem  3
   4 wq:manager                      1  0.000   808/ 1172 244 (244)  w:sem  7
 205 top                           366  2.544  1560/ 1884 255 (255)  RUN    3
  17 dataman                        57  0.000   752/ 1180  90 ( 90)  w:sem  4
  20 wq:lp_default                  19  0.084   724/ 1500 205 (205)  w:sem  7
  22 wq:I2C1                       121  0.508   748/ 1244 248 (248)  READY  7
  27 wq:hp_default                   4  0.000   476/ 1500 243 (243)  w:sem  7
  44 wq:SPI1                      4733 19.168   672/ 1244 254 (254)  READY  7
  49 wq:I2C2                         0  0.000   368/ 1244 247 (247)  w:sem  7
  54 wq:I2C3                        80  0.339   748/ 1244 246 (246)  READY  7
  56 wq:SPI5                         0  0.000   368/ 1244 250 (250)  w:sem  7
  63 wq:SPI4                        63  0.339   536/ 1244 251 (251)  READY  7
  80 sensors                       588  2.544  1256/ 1964 238 (238)  w:sem 11
  83 commander                     234  0.848  1564/ 3212 140 (140)  READY  6
  85 commander_low_prio              0  0.000   656/ 2996  50 ( 50)  w:sem  6
  93 mavlink_if0                  1048  3.562  1648/ 2532 100 (100)  READY  4
  94 mavlink_rcv_if0                78  0.339  1336/ 2836 175 (175)  w:sem  4
 134 gps                            53  0.169  1032/ 1516 209 (209)  w:sem  4
 162 mavlink_if1                   410  1.017  1648/ 2484 100 (100)  w:sig  4
 163 mavlink_rcv_if1                76  0.254  1408/ 2836 175 (175)  w:sem  4
 174 ekf2                         1403  6.361  4536/ 6572 239 (239)  w:sem  4
 178 navigator                      27  0.169   888/ 1764 105 (105)  w:sem  4
 204 log_writer_file                 0  0.000   376/ 1164  60 ( 60)  w:sem 24
 201 logger                        118  0.508  1312/ 3644 234 (234)  w:sem 24

Processes: 27 total, 8 running, 19 sleeping, max FDs: 54
CPU usage: 38.85% tasks, 1.87% sched, 59.29% idle
DMA Memory: 5120 total, 1024 used 1536 peak
Uptime: 34.546s total, 23.070s idle
nsh> sd_bench
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:   316.56 KB/s, max write time: 344 ms (=  11.63 KB/s), fsync: 632 ms
INFO  [sd_bench]   Run  1:   432.32 KB/s, max write time: 163 ms (=  24.54 KB/s), fsync: 11 ms
INFO  [sd_bench]   Run  2:   139.47 KB/s, max write time: 972 ms (=   4.12 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run  3:   471.89 KB/s, max write time: 90 ms (=  44.44 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run  4:   468.45 KB/s, max write time: 56 ms (=  71.43 KB/s), fsync: 4 ms
INFO  [sd_bench]   Avg   :   359.18 KB/s
nsh>

This PR with CONFIG_ARMV7M_DCACHE_WRITETHROUGH=y

 PID COMMAND                   CPU(ms) CPU(%)  USED/STACK PRIO(BASE) STATE FD
   0 Idle Task                   12276 59.287   284/  748   0 (  0)  READY  3
   1 hpwork                          0  0.000   344/ 1780 249 (249)  w:sig  3
   2 lpwork                         12  0.084   580/ 1780  50 ( 50)  w:sig  8
   3 init                          821  0.000  1728/ 2604 100 (100)  w:sem  3
   4 wq:manager                      1  0.000   808/ 1172 244 (244)  w:sem  7
 197 top                           213  2.629  1560/ 1884 255 (255)  RUN    3
  17 dataman                        58  0.000   752/ 1180  90 ( 90)  w:sem  4
  20 wq:lp_default                  14  0.084   724/ 1500 205 (205)  w:sem  7
  22 wq:I2C1                        96  0.508   748/ 1244 248 (248)  READY  7
  27 wq:hp_default                   3  0.000   476/ 1500 243 (243)  w:sem  7
  36 wq:SPI1                      3827 19.168   672/ 1244 254 (254)  READY  7
  41 wq:I2C2                         0  0.000   368/ 1244 247 (247)  w:sem  7
  46 wq:I2C3                        66  0.424   748/ 1244 246 (246)  READY  7
  48 wq:SPI5                         0  0.000   368/ 1244 250 (250)  w:sem  7
  55 wq:SPI4                        48  0.339   536/ 1244 251 (251)  READY  7
  72 sensors                       492  2.629  1328/ 1964 238 (238)  w:sem 11
  74 commander                     206  0.763  1624/ 3212 140 (140)  READY  6
  75 commander_low_prio              0  0.000   560/ 2996  50 ( 50)  w:sem  6
  82 mavlink_if0                   879  3.562  1648/ 2532 100 (100)  READY  4
  83 mavlink_rcv_if0                58  0.254  1424/ 2836 175 (175)  w:sem  4
 121 gps                            41  0.254  1008/ 1516 209 (209)  w:sem  4
 153 mavlink_if1                   358  1.102  1648/ 2484 100 (100)  w:sig  4
 154 mavlink_rcv_if1                68  0.339  1336/ 2836 175 (175)  w:sem  4
 166 ekf2                         1096  6.276  4536/ 6572 239 (239)  w:sem  4
 170 navigator                      20  0.169   888/ 1764 105 (105)  w:sem  4
 188 logger                         91  0.508  1312/ 3644 234 (234)  w:sem 24
 191 log_writer_file                 0  0.000   376/ 1164  60 ( 60)  w:sem 24

Processes: 27 total, 8 running, 19 sleeping, max FDs: 54
CPU usage: 39.10% tasks, 1.61% sched, 59.29% idle
DMA Memory: 5120 total, 1024 used 1024 peak
Uptime: 21.213s total, 12.277s idle
nsh> sd_bench
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:   478.79 KB/s, max write time: 19 ms (= 210.53 KB/s), fsync: 6 ms
INFO  [sd_bench]   Run  1:   199.40 KB/s, max write time: 965 ms (=   4.15 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run  2:   481.35 KB/s, max write time: 13 ms (= 307.69 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run  3:   484.63 KB/s, max write time: 14 ms (= 285.71 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run  4:   339.96 KB/s, max write time: 381 ms (=  10.50 KB/s), fsync: 5 ms
INFO  [sd_bench]   Avg   :   395.08 KB/s
nsh>

This PR with NO d-cache

PID COMMAND                   CPU(ms) CPU(%)  USED/STACK PRIO(BASE) STATE FD
   0 Idle Task                   10738 45.292   284/  748   0 (  0)  READY  3
   1 hpwork                          0  0.000   344/ 1780 249 (249)  w:sig  3
   2 lpwork                         23  0.169   580/ 1780  50 ( 50)  w:sig  8
   3 init                          979  0.000  1728/ 2604 100 (100)  w:sem  3
   4 wq:manager                      2  0.000   808/ 1172 244 (244)  w:sem  7
 197 top                           549  4.240  1560/ 1884 255 (255)  RUN    3
  17 dataman                        82  0.000   752/ 1180  90 ( 90)  w:sem  4
  20 wq:lp_default                  25  0.084   856/ 1500 205 (205)  READY  7
  22 wq:I2C1                       167  0.678   748/ 1244 248 (248)  READY  7
  27 wq:hp_default                   5  0.000   632/ 1500 243 (243)  READY  7
  36 wq:SPI1                      5902 24.173   672/ 1244 254 (254)  READY  7
  41 wq:I2C2                         0  0.000   368/ 1244 247 (247)  w:sem  7
  46 wq:I2C3                       116  0.508   748/ 1244 246 (246)  READY  7
  48 wq:SPI5                         0  0.000   368/ 1244 250 (250)  w:sem  7
  55 wq:SPI4                        85  0.424   536/ 1244 251 (251)  READY  7
  72 sensors                       776  3.223  1172/ 1964 238 (238)  w:sem 11
  74 commander                     468  1.272  1576/ 3212 140 (140)  READY  6
  75 commander_low_prio              0  0.000   560/ 2996  50 ( 50)  w:sem  6
  82 mavlink_if0                  1577  4.495  1648/ 2532 100 (100)  READY  4
  83 mavlink_rcv_if0               112  0.254  1424/ 2836 175 (175)  READY  4
 121 gps                            75  0.339  1136/ 1516 209 (209)  w:sem  4
 153 mavlink_if1                   780  1.357  1648/ 2484 100 (100)  w:sig  4
 154 mavlink_rcv_if1               137  0.424  1424/ 2836 175 (175)  w:sem  4
 166 ekf2                         1929  8.481  4536/ 6572 239 (239)  w:sem  4
 170 navigator                      60  0.339   888/ 1764 105 (105)  w:sem  4
 190 log_writer_file                 0  0.000   376/ 1164  60 ( 60)  w:sem 24
 188 logger                        209  0.932  1312/ 3644 234 (234)  w:sem 24

Processes: 27 total, 11 running, 16 sleeping, max FDs: 54
CPU usage: 51.40% tasks, 3.31% sched, 45.29% idle
DMA Memory: 5120 total, 1024 used 1024 peak
Uptime: 25.782s total, 10.739s idle
nsh> sd_bench
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.20 KB/s, max write time: 368 ms (=  10.87 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run  1:   386.68 KB/s, max write time: 272 ms (=  14.71 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run  2:   450.55 KB/s, max write time: 13 ms (= 307.69 KB/s), fsync: 4 ms
INFO  [sd_bench]   Run  3:   324.16 KB/s, max write time: 519 ms (=   7.71 KB/s), fsync: 5 ms
INFO  [sd_bench]   Run  4:   448.22 KB/s, max write time: 17 ms (= 235.29 KB/s), fsync: 4 ms
INFO  [sd_bench]   Avg   :   388.15 KB/s
nsh>

@dagar dagar merged commit d4cd1d0 into master Jul 10, 2019
@dagar dagar deleted the pr-f7_dcache branch July 10, 2019 23:08
@bkueng bkueng mentioned this pull request Jul 11, 2019
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

NuttX STM32F7 write-back dcache
5 participants