mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
HAL_PX4: change dma_allocate api to malloc_type
This commit is contained in:
parent
9d6ab78376
commit
e591265329
@ -244,18 +244,26 @@ extern "C" {
|
||||
allocate DMA-capable memory if possible. Otherwise return normal
|
||||
memory.
|
||||
*/
|
||||
void *PX4Util::dma_allocate(size_t size)
|
||||
void *PX4Util::malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type)
|
||||
{
|
||||
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
return fat_dma_alloc(size);
|
||||
if (mem_type == AP_HAL::Util::MEM_DMA_SAFE) {
|
||||
return fat_dma_alloc(size);
|
||||
} else {
|
||||
return malloc(size);
|
||||
}
|
||||
#else
|
||||
return malloc(size);
|
||||
#endif
|
||||
}
|
||||
void PX4Util::dma_free(void *ptr, size_t size)
|
||||
void PX4Util::free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type)
|
||||
{
|
||||
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
fat_dma_free(ptr, size);
|
||||
if (mem_type == AP_HAL::Util::MEM_DMA_SAFE) {
|
||||
return fat_dma_free(ptr, size);
|
||||
} else {
|
||||
return free(ptr);
|
||||
}
|
||||
#else
|
||||
return free(ptr);
|
||||
#endif
|
||||
|
@ -62,9 +62,9 @@ public:
|
||||
void set_imu_target_temp(int8_t *target) override;
|
||||
|
||||
// allocate and free DMA-capable memory if possible. Otherwise return normal memory
|
||||
void *dma_allocate(size_t size) override;
|
||||
void dma_free(void *ptr, size_t size) override;
|
||||
|
||||
void *malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type) override;
|
||||
void free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type) override;
|
||||
|
||||
private:
|
||||
int _safety_handle;
|
||||
PX4::NSHShellStream _shell_stream;
|
||||
|
Loading…
Reference in New Issue
Block a user