Closed ShiauweiZhao closed 4 years ago
same as #13483
This is still a problem.
We use our own boards with stm32h7 in it.And we referred to the Durandal code, also had the problem.I found the bug and solved it.
The STM32H7 series contains two SDMMC controllers: SDMMC1 and SDMMC2, we use SDMMC1 as the default. SDMMC1 can not constitute the bus matrix with SRAM1 or SRAM2,if you use IDMA, in fact,SDMMC1 can only access memory of AXI SRAM area for IDMA.
In function stm32_dmapreflight(..) does not judge the memory region. IDMA used invalid address(from userspace ) to generate TXUNDERR error. The correct thing to do is to add the following code to the function stm32_dmapreflight(...)
static int stm32_dmapreflight(FAR struct sdio_dev_s dev, FAR const uint8_t buffer, size_t buflen) { ......
if((uintptr_t)buffer < STM32_AXISRAM_BASE ||(uintptr_t)buffer> STM32_AXISRAM_BASE + 512*1024 ){
return -EFAULT;
}
return 0;
}
If the FAT file system finds a write failure and it will try write again with the STM32_AXISRAM_BASE region memory address.then everything is ok.
I temporarily closed CONFIG_STM32H7_SDMMC_IDMA in deconfig
We use our own boards with stm32h7 in it.And we referred to the Durandal code, also had the problem.I found the bug and solved it.
The STM32H7 series contains two SDMMC controllers: SDMMC1 and SDMMC2, we use SDMMC1 as the default. SDMMC1 can not constitute the bus matrix with SRAM1 or SRAM2,if you use IDMA, in fact,SDMMC1 can only access memory of AXI SRAM area for IDMA.
In function stm32_dmapreflight(..) does not judge the memory region. IDMA used invalid address(from userspace ) to generate TXUNDERR error. The correct thing to do is to add the following code to the function stm32_dmapreflight(...)
static int stm32_dmapreflight(FAR struct sdio_dev_s dev, FAR const uint8_t buffer, size_t buflen) { ......
if((uintptr_t)buffer < STM32_AXISRAM_BASE ||(uintptr_t)buffer> STM32_AXISRAM_BASE + 512*1024 ){ return -EFAULT; } return 0;
}
If the FAT file system finds a write failure and it will try write again with the STM32_AXISRAM_BASE region memory address.then everything is ok.
In PX4 The DMA Alocator is is used board_dma_alloc(). This memory is allocated statically from AIX SRAM to begin with with proper DMA / D-cache alignment and sizing.
Both SDMMC1 & SDMMC2 support IAX SRAM in IDMA mode.
ONLY SDMMC2 can access SRAM[123] so to upstream this change it would have to dependent on the SDMMC choice and its ranges. But this is un necessary in the PX4 use case.
@zhaoxiaowei1013 & @merrock please test with https://github.com/PX4/NuttX/pull/106
But this is un necessary in the PX4 use case.
My above statement is incorrect for writes from user space. I see what you were facing. It was fixed in upstream and I have back ported it.
Yes, it works well.
In fact, I ported the stm32h7 driver to 1.9 from 1.11,I can't experiment on 1.11. Besides, I found several other problems
sd card can not be formatted related to idma mkfatfs /dev/mmcsd0 will return an error.
(1) apps/fsutils/mkfatfs/writefat.c In the function 'int mkfatfs(FAR const char pathname, FAR struct fat_format_s fmt) var.fv_sect = (FAR uint8_t )malloc(var.fv_sectorsize); modified to var.fv_sect = (FAR uint8_t )memalign(32,var.fv_sectorsize); Otherwise, stm32_dmapreflight will fail sometime.
(2) nuttx\drivers\bch\bchlib_setup.c In the function 'bchlib_setup' bch->buffer = (FAR uint8_t )kmm_malloc(bch->sectsize); modified to bch->buffer = (FAR uint8_t )fat_dma_alloc(bch->sectsize);
(3) drivers/bch/bchlib_write.c ret = bch->inode->u.i_bops->write(bch->inode, (FAR uint8_t *)buffer, sector, nsectors); buffer is still a user space address. The module does not have the mechanism of FAT. My solution is to request an address area in AXI SRAM and copy the buffer content to the request address area.
In addition, when entering the 'logger on' command, if no GPS is connected at this time, the QGC will display error characters, the reason is When creating the log file name, the get_log_time function in px4_firmware\src\modules\logger\util.cpp will be called the code 'int vehicle_gps_position_sub = orb_subscribe(ORB_ID(vehicle_gps_position));' will publish a gps messages. mavlink module in mavlink_messagess.cpp -->MavlinkStreamGPSRawInt class if (_gps_sub->update(&_gps_time, &gps)) { ... mavlink_msg_gps_raw_int_send_struct(...); } This Judgment will come true. The data packets that error garbled characters were sent to the ground station. My solution is to add time to judge if (_gps_sub->update(&_gps_time, &gps)) { if(_gps_time> 0){ ... mavlink_msg_gps_raw_int_send_struct(...); } }
These were added by me temporarily,it works well. This is for reference only.
This issue has been automatically marked as stale because it has not had recent activity. Thank you for your contributions.
Starting logger on Durandal (master branch) manually from Mavlink console seems to fail: