From 6f28c61c8d7f72e9a0640e5aad953c380a1c2355 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 24 Nov 2016 09:06:42 +1100 Subject: [PATCH] AP_InertialSensor: changed SIZE to LEN thanks to Lucas for suggestion --- libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp | 6 +++--- libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index 1a480788bf..126c036fc7 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -230,7 +230,7 @@ extern const AP_HAL::HAL& hal; #define MPU_SAMPLE_SIZE 14 #define MPU_FIFO_DOWNSAMPLE_COUNT 8 -#define MPU_FIFO_BUFFER_SIZE 16 +#define MPU_FIFO_BUFFER_LEN 16 #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]) @@ -415,7 +415,7 @@ void AP_InertialSensor_MPU6000::start() set_accel_orientation(_accel_instance, _rotation); // allocate fifo buffer - _fifo_buffer = (uint8_t *)hal.util->dma_allocate(MPU_FIFO_BUFFER_SIZE * MPU_SAMPLE_SIZE); + _fifo_buffer = (uint8_t *)hal.util->dma_allocate(MPU_FIFO_BUFFER_LEN * MPU_SAMPLE_SIZE); if (_fifo_buffer == nullptr) { AP_HAL::panic("MPU6000: Unable to allocate FIFO buffer"); } @@ -644,7 +644,7 @@ void AP_InertialSensor_MPU6000::_read_fifo() } while (n_samples > 0) { - uint8_t n = MIN(n_samples, MPU_FIFO_BUFFER_SIZE); + uint8_t n = MIN(n_samples, MPU_FIFO_BUFFER_LEN); if (!_block_read(MPUREG_FIFO_R_W, rx, n * MPU_SAMPLE_SIZE)) { printf("MPU60x0: error in fifo read %u bytes\n", n * MPU_SAMPLE_SIZE); goto check_registers; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp index cb61981c55..e5065eed48 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp @@ -189,7 +189,7 @@ extern const AP_HAL::HAL &hal; #define MPU_SAMPLE_SIZE 14 #define MPU_FIFO_DOWNSAMPLE_COUNT 8 -#define MPU_FIFO_BUFFER_SIZE 16 +#define MPU_FIFO_BUFFER_LEN 16 #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]) @@ -359,7 +359,7 @@ void AP_InertialSensor_MPU9250::start() set_accel_orientation(_accel_instance, _rotation); // allocate fifo buffer - _fifo_buffer = (uint8_t *)hal.util->dma_allocate(MPU_FIFO_BUFFER_SIZE * MPU_SAMPLE_SIZE); + _fifo_buffer = (uint8_t *)hal.util->dma_allocate(MPU_FIFO_BUFFER_LEN * MPU_SAMPLE_SIZE); if (_fifo_buffer == nullptr) { AP_HAL::panic("MPU9250: Unable to allocate FIFO buffer"); } @@ -577,7 +577,7 @@ bool AP_InertialSensor_MPU9250::_read_sample() } while (n_samples > 0) { - uint8_t n = MIN(MPU_FIFO_BUFFER_SIZE, n_samples); + uint8_t n = MIN(MPU_FIFO_BUFFER_LEN, n_samples); if (!_block_read(MPUREG_FIFO_R_W, rx, n * MPU_SAMPLE_SIZE)) { printf("MPU60x0: error in fifo read %u bytes\n", n * MPU_SAMPLE_SIZE); goto check_registers;