nxp_fmurt1062-v1:Force no no-unaligned-access

This results in a load saving (no dcache) of 16.82% at a cost
  of 0.03% Flash, .07% XIP Flash and .45% SRAM

Forced Alighment

With: -mno-unaligned-access

Memory region         Used Size  Region Size  %age Used
           flash:      606568 B         7 MB      8.26%
        flashxip:      622920 B         1 MB     59.41%
            sram:      640848 B       856 KB     73.11%
            itcm:          0 GB         0 GB
            dtcm:          0 GB       128 KB      0.00%

 PID COMMAND                   CP
   0 Idle Task                   87640 20.047   204/  748   0 (  0)  READY  3
   1 hpwork                          0  0.000   332/ 1784 249 (249)  w:sig  3
   2 lpwork                         26  0.008   780/ 1616  50 ( 50)  w:sig  4
   3 init                            0  0.000  1980/ 2928 100 (100)  w:sem  3
   4 wq:manager                      0  0.000   508/ 1256 255 (255)  w:sem  4
 327 navigator                     910  0.204  1124/ 1832 105 (105)  READY  6
  23 wq:lp_default                3479  0.795  1252/ 1920 205 (205)  READY  4
  30 wq:hp_default               23554  5.415  1332/ 1904 237 (237)  READY  4
  47 dataman                         0  0.000   820/ 1208  90 ( 90)  w:sem  4
  57 wq:I2C1                     26849  6.190  1060/ 2336 246 (246)  w:sem  4
  60 wq:I2C2                     24045  5.440   732/ 2336 245 (245)  w:sem  4
  86 wq:SPI1                     47127 10.804  1352/ 2336 253 (253)  w:sem  4
  91 wq:I2C3                      1935  0.436   980/ 2336 244 (244)  w:sem  4
 101 wq:SPI3                      6932  1.585  1028/ 2336 251 (251)  w:sem  4
 237 wq:nav_and_controllers      16743  3.832  1236/ 2240 242 (242)  w:sem  4
 248 wq:rate_ctrl                 9008  2.074  1572/ 1952 255 (255)  w:sem  4
 250 wq:INS0                     37182  8.450  4372/ 6000 241 (241)  w:sem  4
 264 commander                   29395  6.732  1260/ 3224 140 (140)  READY  5
 287 mavlink_if0                 60513 13.828  1876/ 2728 100 (100)  READY  4
 294 mavlink_rcv_if0              5946  1.387  1292/ 4560 175 (175)  READY  4
 307 wq:UART5                     3345  0.770   844/ 1632 229 (229)  READY  4
 370 log_writer_file                 0  0.000   372/ 1176  60 ( 60)  w:sem  3
 369 logger                       2121  0.484  2468/ 3648 230 (230)  READY  3
 393 top                         37523  8.641  3060/ 4080 237 (237)  RUN    3

Processes: 24 total, 10 running, 14 sleeping
CPU usage: 77.08% tasks, 2.87% sched, 20.05% idle
DMA Memory: 5120 total, 1024 used 1024 peak
Uptime: 441.946s total, 87.640s idle

Allow Un-Alighment
With Out: -mno-unaligned-access
Memory region         Used Size  Region Size  %age Used
           flash:      604008 B         7 MB      8.23%   8.26%    +0.03

        flashxip:      622240 B         1 MB     59.34%  59.41%    +0.07
            sram:      636752 B       856 KB     72.64%  73.11%    +0.45
            itcm:          0 GB         0 GB
            dtcm:          0 GB       128 KB      0.00%  0.00%

 PID COMMAND                   CPU(ms) CPU(%)  USED/STACK PRIO(BASE) STATE FD
   0 Idle Task                    2418  3.190   264/  748   0 (  0)  READY  3
   1 hpwork                          0  0.000   332/ 1784 249 (249)  w:sig  3
   2 lpwork                         12  0.004   852/ 1616  50 ( 50)  w:sig  3
   3 init                            0  0.000  1932/ 2928 100 (100)  w:sem  3
   4 wq:manager                      0  0.000   548/ 1256 255 (255)  w:sem  4
 327 navigator                      22  0.203  1052/ 1832 105 (105)  READY  6
  23 wq:lp_default                  83  0.743  1252/ 1920 205 (205)  READY  4
  30 wq:hp_default                 637  5.886  1332/ 1904 237 (237)  READY  4
  47 dataman                         0  0.000   820/ 1208  90 ( 90)  w:sem  4
  57 wq:I2C1                       162  1.063  1060/ 2336 246 (246)  w:sem  4
  60 wq:I2C2                        98  0.500   732/ 2336 245 (245)  w:sem  4
  86 wq:SPI1                      1166 10.771  1352/ 2336 253 (253)  w:sem  4
  91 wq:I2C3                        48  0.437  1060/ 2336 244 (244)  w:sem  4
 101 wq:SPI3                       178  1.653  1028/ 2336 251 (251)  w:sem  4
 237 wq:nav_and_controllers        410  3.781  1324/ 2240 242 (242)  w:sem  4
 248 wq:rate_ctrl                  222  2.050  1572/ 1952 255 (255)  w:sem  4
 250 wq:INS0                       940  8.691  4372/ 6000 241 (241)  w:sem  4
 264 commander                     753  6.475  1472/ 3224 140 (140)  READY  5.03
 287 mavlink_if0                  1440 13.973  1780/ 2728 100 (100)  READY  4
 294 mavlink_rcv_if0               139  1.304  1276/ 4560 175 (175)  READY  4
 307 wq:UART5                       83  0.785   828/ 1632 229 (229)  READY  4
 370 log_writer_file                 0  0.000   372/ 1176  60 ( 60)  w:sem  3
 369 logger                         54  0.493  2468/ 3648 230 (230)  READY  3
 393 top                          1053 10.015  3060/ 4080 237 (237)  RUN    3
 396 mavlink_rcv_if1               166  1.608  1380/ 4560 175 (175)  READY  4
 395 mavlink_if1                  2167 23.459  1812/ 2824 100 (100)  READY  4

Processes: 26 total, 12 running, 14 sleeping
CPU usage: 93.90% tasks, 2.91% sched, 3.19% idle     77.08% tasks, 2.87% sched, 20.05% idle -16.82%
DMA Memory: 5120 total, 1024 used 1024 peak
Uptime: 18.242s total, 2.419s idle
This commit is contained in:
David Sidrane 2021-10-27 13:38:25 -07:00 committed by Daniel Agar
parent 4225193456
commit dedad87e82
1 changed files with 1 additions and 0 deletions

View File

@ -29,6 +29,7 @@ CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARM_MPU=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_CUSTOM_LEDS=y
CONFIG_BOARD_FORCE_ALIGNMENT=y
CONFIG_BOARD_LOOPSPERMSEC=104926
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BOOT_RUNFROMISRAM=y