mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: use non-cachable SRAM3 for DMA on H743
Adjust SRAM1+SRAM2 to 256k as describe in the H743 reference manual Provide access to mem_info() information Co-authored-by: Andrew Tridgell <andrew@tridgell.net>
This commit is contained in:
parent
cfac268f13
commit
2cdc202d19
|
@ -378,6 +378,28 @@ void Util::dma_info(ExpandingString &str)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if CH_CFG_USE_HEAP == TRUE
|
||||
/*
|
||||
return information on heap usage
|
||||
*/
|
||||
void Util::mem_info(ExpandingString &str)
|
||||
{
|
||||
memory_heap_t *heaps;
|
||||
const struct memory_region *regions;
|
||||
uint8_t num_heaps = malloc_get_heaps(&heaps, ®ions);
|
||||
|
||||
str.printf("MemInfoV1\n");
|
||||
for (uint8_t i=0; i<num_heaps; i++) {
|
||||
size_t totalp=0, largest=0;
|
||||
// get memory available on main heap
|
||||
chHeapStatus(i == 0 ? nullptr : &heaps[i], &totalp, &largest);
|
||||
str.printf("START=0x%08x LEN=%3uk FREE=%6u LRG=%6u TYPE=%1u\n",
|
||||
unsigned(regions[i].address), unsigned(regions[i].size/1024),
|
||||
unsigned(totalp), unsigned(largest), unsigned(regions[i].flags));
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if HAL_ENABLE_SAVE_PERSISTENT_PARAMS
|
||||
|
||||
static const char *persistent_header = "{{PERSISTENT_START_V1}}\n";
|
||||
|
@ -485,6 +507,4 @@ void Util::apply_persistent_params(void) const
|
|||
unsigned(count), unsigned(errors));
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAL_ENABLE_SAVE_PERSISTENT_PARAMS
|
||||
|
||||
|
|
|
@ -75,6 +75,9 @@ public:
|
|||
// request information on dma contention
|
||||
void dma_info(ExpandingString &str) override;
|
||||
#endif
|
||||
#if CH_CFG_USE_HEAP == TRUE
|
||||
void mem_info(ExpandingString &str) override;
|
||||
#endif
|
||||
|
||||
#if HAL_ENABLE_SAVE_PERSISTENT_PARAMS
|
||||
// apply persistent parameters to current parameters
|
||||
|
|
|
@ -40,16 +40,11 @@
|
|||
#define MEM_REGION_FLAG_FAST 2
|
||||
#define MEM_REGION_FLAG_SDCARD 4
|
||||
|
||||
static const struct memory_region {
|
||||
void *address;
|
||||
uint32_t size;
|
||||
uint32_t flags;
|
||||
} memory_regions[] = { HAL_MEMORY_REGIONS };
|
||||
|
||||
#ifdef HAL_CHIBIOS_ENABLE_MALLOC_GUARD
|
||||
static mutex_t mem_mutex;
|
||||
#endif
|
||||
|
||||
static const struct memory_region memory_regions[] = { HAL_MEMORY_REGIONS };
|
||||
// the first memory region is already setup as the ChibiOS
|
||||
// default heap, so we will index from 1 in the allocators
|
||||
#define NUM_MEMORY_REGIONS (sizeof(memory_regions)/sizeof(memory_regions[0]))
|
||||
|
@ -450,6 +445,16 @@ thread_t *thread_create_alloc(size_t size,
|
|||
return NULL;
|
||||
}
|
||||
|
||||
/*
|
||||
return heap information
|
||||
*/
|
||||
uint8_t malloc_get_heaps(memory_heap_t **_heaps, const struct memory_region **regions)
|
||||
{
|
||||
*_heaps = &heaps[0];
|
||||
*regions = &memory_regions[0];
|
||||
return NUM_MEMORY_REGIONS;
|
||||
}
|
||||
|
||||
#endif // CH_CFG_USE_HEAP
|
||||
|
||||
|
||||
|
|
|
@ -35,6 +35,15 @@ void *malloc_sdcard_dma(size_t size);
|
|||
void *malloc_fastmem(size_t size);
|
||||
thread_t *thread_create_alloc(size_t size, const char *name, tprio_t prio, tfunc_t pf, void *arg);
|
||||
|
||||
struct memory_region {
|
||||
void *address;
|
||||
uint32_t size;
|
||||
uint32_t flags;
|
||||
};
|
||||
#if CH_CFG_USE_HEAP == TRUE
|
||||
uint8_t malloc_get_heaps(memory_heap_t **_heaps, const struct memory_region **regions);
|
||||
#endif
|
||||
|
||||
// flush all dcache
|
||||
void memory_flush_all(void);
|
||||
|
||||
|
|
|
@ -20,10 +20,11 @@ mcu = {
|
|||
# flags of 4 means memory can be used for SDMMC DMA
|
||||
'RAM_MAP' : [
|
||||
(0x20000000, 128, 2), # DTCM, tightly coupled, no DMA, fast
|
||||
(0x30000000, 288, 0), # SRAM1, SRAM2, SRAM3
|
||||
(0x38000000, 64, 1), # SRAM4. This supports both DMA and BDMA ops
|
||||
(0x30000000, 256, 0), # SRAM1, SRAM2
|
||||
(0x38000000, 64, 0), # SRAM4.
|
||||
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
(0x30040000, 32, 1), # SRAM3. This supports both DMA and BDMA ops.
|
||||
],
|
||||
|
||||
'EXPECTED_CLOCK' : 400000000,
|
||||
|
|
Loading…
Reference in New Issue