mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_InertialSensor: reduce FIFO buffer size to avoid DMA contention
This commit is contained in:
parent
062c6cef41
commit
3db6203fb6
@ -55,7 +55,7 @@ extern const AP_HAL::HAL& hal;
|
||||
#include "AP_InertialSensor_Invensense_registers.h"
|
||||
|
||||
#define MPU_SAMPLE_SIZE 14
|
||||
#define MPU_FIFO_BUFFER_LEN 16
|
||||
#define MPU_FIFO_BUFFER_LEN 8
|
||||
|
||||
#define int16_val(v, idx) ((int16_t)(((uint16_t)v[2*idx] << 8) | v[2*idx+1]))
|
||||
#define uint16_val(v, idx)(((uint16_t)v[2*idx] << 8) | v[2*idx+1])
|
||||
|
@ -51,7 +51,7 @@ static const float GYRO_SCALE = (0.0174532f / 16.4f);
|
||||
#include "AP_InertialSensor_Invensensev2_registers.h"
|
||||
|
||||
#define INV2_SAMPLE_SIZE 14
|
||||
#define INV2_FIFO_BUFFER_LEN 16
|
||||
#define INV2_FIFO_BUFFER_LEN 8
|
||||
|
||||
#define int16_val(v, idx) ((int16_t)(((uint16_t)v[2*idx] << 8) | v[2*idx+1]))
|
||||
#define uint16_val(v, idx)(((uint16_t)v[2*idx] << 8) | v[2*idx+1])
|
||||
|
Loading…
Reference in New Issue
Block a user