mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_InertialSensor: enable fast sampling for aerofc
This commit is contained in:
parent
1018129ed9
commit
2e4e4365d0
@ -242,8 +242,7 @@ extern "C" {
|
||||
*/
|
||||
void *PX4Util::dma_allocate(size_t size)
|
||||
{
|
||||
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1) && \
|
||||
!defined(CONFIG_ARCH_BOARD_AEROFC_V1)
|
||||
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
return fat_dma_alloc(size);
|
||||
#else
|
||||
return malloc(size);
|
||||
@ -251,8 +250,7 @@ void *PX4Util::dma_allocate(size_t size)
|
||||
}
|
||||
void PX4Util::dma_free(void *ptr, size_t size)
|
||||
{
|
||||
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1) && \
|
||||
!defined(CONFIG_ARCH_BOARD_AEROFC_V1)
|
||||
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
fat_dma_free(ptr, size);
|
||||
#else
|
||||
return free(ptr);
|
||||
|
@ -743,6 +743,7 @@ AP_InertialSensor::detect_backends(void)
|
||||
break;
|
||||
|
||||
case AP_BoardConfig::PX4_BOARD_AEROFC:
|
||||
_fast_sampling_mask.set_default(1);
|
||||
_add_backend(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU6500_NAME), ROTATION_YAW_270));
|
||||
break;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user