Skip to content

Commit

Permalink
new mpu9250 driver using FIFOs and raw sampling (8 kHz gyro, 4 kHz ac…
Browse files Browse the repository at this point in the history
…cel)
  • Loading branch information
dagar committed Jan 30, 2020
1 parent 931a3f2 commit a46cd55
Show file tree
Hide file tree
Showing 12 changed files with 895 additions and 23 deletions.
1 change: 1 addition & 0 deletions boards/px4/fmu-v3/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ px4_add_board(
imu/mpu6000
imu/mpu9250
imu/icm20948
#imu/invensense/mpu9250 # WIP
irlock
lights/blinkm
lights/rgbled
Expand Down
20 changes: 2 additions & 18 deletions boards/px4/fmu-v3/nuttx-config/include/board.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@
/************************************************************************************
* Included Files
************************************************************************************/
#include "board_dma_map.h"

#include <nuttx/config.h>
#ifndef __ASSEMBLY__
Expand All @@ -53,7 +54,7 @@
************************************************************************************/

/* Clocking *************************************************************************/
/* The PX4FMUV2 uses a 24MHz crystal connected to the HSE.
/* The PX4FMUV3 uses a 24MHz crystal connected to the HSE.
*
* This is the "standard" configuration as set up by arch/arm/src/stm32f40xx_rcc.c:
* System Clock source : PLL (HSE)
Expand Down Expand Up @@ -195,17 +196,6 @@
# define SDIO_SDXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT)
#endif

/* DMA Channl/Stream Selections *****************************************************/
/* Stream selections are arbitrary for now but might become important in the future
* is we set aside more DMA channels/streams.
*
* SDIO DMA
*   DMAMAP_SDIO_1 = Channel 4, Stream 3 <- may later be used by SPI DMA
*   DMAMAP_SDIO_2 = Channel 4, Stream 6
*/

#define DMAMAP_SDIO DMAMAP_SDIO_1

/* Alternate function pin selections ************************************************/

/* UARTs */
Expand Down Expand Up @@ -234,10 +224,6 @@

/* UART8 has no alternate pin config */

/* UART RX DMA configurations */

#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2

/* CAN
*
* CAN1 is routed to the onboard transceiver.
Expand Down Expand Up @@ -323,8 +309,6 @@
# define PROBE_MARK(n)
#endif



/************************************************************************************
* Public Data
************************************************************************************/
Expand Down
28 changes: 28 additions & 0 deletions boards/px4/fmu-v3/nuttx-config/include/board_dma_map.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
#pragma once

/* DMA Channel/Stream Selections
*
* DMAMAP_USART3_RX = DMA1, Stream 1, Channel 4
* DMAMAP_UART4_RX = DMA1, Stream 2, Channel 4
* DMAMAP_UART7_RX = DMA1, Stream 3, Channel 5
* DMAMAP_USART2_RX = DMA1, Stream 5, Channel 4
* DMAMAP_TIM4_UP = DMA1, Stream 6, Channel 2
*
*   DMAMAP_SPI4_RX_1 = DMA2, Stream 0, Channel 4
*   DMAMAP_USART6_RX_1 = DMA2, Stream 1, Channel 5
*   DMAMAP_SPI1_RX_2 = DMA2, Stream 2, Channel 3
*   DMAMAP_SPI1_TX_1 = DMA2, Stream 3, Channel 3
* DMAMAP_SPI4_TX_2 = DMA2, Stream 4, Channel 5
* DMAMAP_TIM1_UP = DMA2, Stream 5, Channel 6
*   DMAMAP_SDIO_2 = DMA2, Stream 6, Channel 4
*   DMAMAP_USART6_TX_2 = DMA2, Stream 7, Channel 5
*
*/

#define DMACHAN_SPI4_RX DMAMAP_SPI4_RX_1
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_1
#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_2
#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_1
#define DMACHAN_SPI4_TX DMAMAP_SPI4_TX_2
#define DMAMAP_SDIO DMAMAP_SDIO_2
#define DMAMAP_USART6_TX DMAMAP_USART6_TX_2
3 changes: 3 additions & 0 deletions boards/px4/fmu-v3/nuttx-config/nsh/defconfig
Original file line number Diff line number Diff line change
Expand Up @@ -187,8 +187,11 @@ CONFIG_STM32_SDIO_CARD=y
CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32_SPI1=y
CONFIG_STM32_SPI1_DMA=y
CONFIG_STM32_SPI2=y
CONFIG_STM32_SPI4=y
CONFIG_STM32_SPI4_DMA=y
CONFIG_STM32_SPI_DMA=y
CONFIG_STM32_TIM10=y
CONFIG_STM32_TIM11=y
CONFIG_STM32_TIM1=y
Expand Down
8 changes: 4 additions & 4 deletions boards/px4/fmu-v3/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,8 +73,8 @@
#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX
#define PX4IO_SERIAL_BASE STM32_USART6_BASE /* hardwired on the board */
#define PX4IO_SERIAL_VECTOR STM32_IRQ_USART6
#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX_2
#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX_2
#define PX4IO_SERIAL_TX_DMAMAP DMAMAP_USART6_TX
#define PX4IO_SERIAL_RX_DMAMAP DMAMAP_USART6_RX
#define PX4IO_SERIAL_RCC_REG STM32_RCC_APB2ENR
#define PX4IO_SERIAL_RCC_EN RCC_APB2ENR_USART6EN
#define PX4IO_SERIAL_CLOCK STM32_PCLK2_FREQUENCY
Expand Down Expand Up @@ -463,8 +463,8 @@

#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS

/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board provides a DMA pool and APIs. */
#define BOARD_DMA_ALLOC_POOL_SIZE (5120 + 512 + 512) // 5120 fat + 512 + 512 spi

#define BOARD_HAS_ON_RESET 1

Expand Down
2 changes: 1 addition & 1 deletion boards/px4/fmu-v3/src/timer_config.c
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
****************************************************************************/

/*
* @file px4fmu_timer_config.c
* @file timer_config.c
*
* Configuration data for the stm32 pwm_servo, input capture and pwm input driver.
*
Expand Down
1 change: 1 addition & 0 deletions boards/px4/fmu-v4/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@ px4_add_board(
imu/adis16497
imu/invensense/icm20602
imu/invensense/icm20608-g
#imu/invensense/mpu9250 # WIP
imu/mpu6000
imu/mpu9250
irlock
Expand Down
46 changes: 46 additions & 0 deletions src/drivers/imu/invensense/mpu9250/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
############################################################################
#
# Copyright (c) 2020 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################

px4_add_module(
MODULE drivers__imu__invensense__mpu9250
MAIN mpu9250
COMPILE_FLAGS
SRCS
MPU9250.cpp
MPU9250.hpp
mpu9250_main.cpp
DEPENDS
drivers_accelerometer
drivers_gyroscope
px4_work_queue
)
177 changes: 177 additions & 0 deletions src/drivers/imu/invensense/mpu9250/InvenSense_MPU9250_registers.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,177 @@
/****************************************************************************
*
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/

/**
* @file InvenSense_MPU9250_registers.hpp
*
* Invensense MPU9250 registers.
*
*/

#pragma once

// TODO: move to a central header
static constexpr uint8_t Bit0 = (1 << 0);
static constexpr uint8_t Bit1 = (1 << 1);
static constexpr uint8_t Bit2 = (1 << 2);
static constexpr uint8_t Bit3 = (1 << 3);
static constexpr uint8_t Bit4 = (1 << 4);
static constexpr uint8_t Bit5 = (1 << 5);
static constexpr uint8_t Bit6 = (1 << 6);
static constexpr uint8_t Bit7 = (1 << 7);

namespace InvenSense_MPU9250
{
static constexpr uint32_t SPI_SPEED = 20 * 1000 * 1000;
static constexpr uint8_t DIR_READ = 0x80;

static constexpr uint8_t WHOAMI = 0x71;

enum class Register : uint8_t {
CONFIG = 0x1A,
GYRO_CONFIG = 0x1B,
ACCEL_CONFIG = 0x1C,
ACCEL_CONFIG2 = 0x1D,

FIFO_EN = 0x23,

INT_STATUS = 0x3A,

INT_PIN_CFG = 0x37,
INT_ENABLE = 0x38,

TEMP_OUT_H = 0x41,
TEMP_OUT_L = 0x42,

USER_CTRL = 0x6A,
PWR_MGMT_1 = 0x6B,

FIFO_COUNTH = 0x72,
FIFO_COUNTL = 0x73,
FIFO_R_W = 0x74,
WHO_AM_I = 0x75,
};

// CONFIG
enum CONFIG_BIT : uint8_t {
FIFO_MODE = Bit6, // when the FIFO is full, additional writes will not be written to FIFO

DLPF_CFG_BYPASS_DLPF_8KHZ = 7, // Rate 8 kHz [2:0]
};

// GYRO_CONFIG
enum GYRO_CONFIG_BIT : uint8_t {
// GYRO_FS_SEL [4:3]
GYRO_FS_SEL_250_DPS = 0, // 0b00000
GYRO_FS_SEL_500_DPS = Bit3, // 0b01000
GYRO_FS_SEL_1000_DPS = Bit4, // 0b10000
GYRO_FS_SEL_2000_DPS = Bit4 | Bit3, // 0b11000

// FCHOICE_B [1:0]
FCHOICE_B_8KHZ_BYPASS_DLPF = Bit1 | Bit0, // 0b10 - 3-dB BW: 3281 Noise BW (Hz): 3451.0 8 kHz
};

// ACCEL_CONFIG
enum ACCEL_CONFIG_BIT : uint8_t {
// ACCEL_FS_SEL [4:3]
ACCEL_FS_SEL_2G = 0, // 0b00000
ACCEL_FS_SEL_4G = Bit3, // 0b01000
ACCEL_FS_SEL_8G = Bit4, // 0b10000
ACCEL_FS_SEL_16G = Bit4 | Bit3, // 0b11000
};

// ACCEL_CONFIG2
enum ACCEL_CONFIG2_BIT : uint8_t {
ACCEL_FCHOICE_B_BYPASS_DLPF = Bit3,
};

// FIFO_EN
enum FIFO_EN_BIT : uint8_t {
TEMP_OUT = Bit7,
GYRO_XOUT = Bit6,
GYRO_YOUT = Bit5,
GYRO_ZOUT = Bit4,
ACCEL = Bit3,
};

// INT_ENABLE
enum INT_ENABLE_BIT : uint8_t {
FIFO_OFLOW_EN = Bit4,
DATA_RDY_INT_EN = Bit0
};

// INT_STATUS
enum INT_STATUS_BIT : uint8_t {
FIFO_OFLOW_INT = Bit4,
DATA_RDY_INT = Bit0,
};

// USER_CTRL
enum USER_CTRL_BIT : uint8_t {
FIFO_EN = Bit6,
FIFO_RST = Bit2,
};

// PWR_MGMT_1
enum PWR_MGMT_1_BIT : uint8_t {
H_RESET = Bit7,

CLKSEL_2 = Bit2,
CLKSEL_1 = Bit1,
CLKSEL_0 = Bit0,
};


namespace FIFO
{
static constexpr size_t SIZE = 512;

// FIFO_DATA layout when FIFO_EN has GYRO_{X, Y, Z}OUT and ACCEL set
struct DATA {
uint8_t ACCEL_XOUT_H;
uint8_t ACCEL_XOUT_L;
uint8_t ACCEL_YOUT_H;
uint8_t ACCEL_YOUT_L;
uint8_t ACCEL_ZOUT_H;
uint8_t ACCEL_ZOUT_L;
uint8_t GYRO_XOUT_H;
uint8_t GYRO_XOUT_L;
uint8_t GYRO_YOUT_H;
uint8_t GYRO_YOUT_L;
uint8_t GYRO_ZOUT_H;
uint8_t GYRO_ZOUT_L;
};
static_assert(sizeof(DATA) == 12);
}

} // namespace InvenSense_MPU9250
Loading

0 comments on commit a46cd55

Please sign in to comment.