Skip to content

Commit

Permalink
ICM20602 and ICM20608-G: new standalone driver (8 kHz gyro, 4 kHz accel)
Browse files Browse the repository at this point in the history
     - uses the FIFO and SPI DMA
     - currently implemented on px4_fmu-v4 only
     - clip counters
     - new low pass filter that operates on an array of data (LowPassFilter2pArray)
     - new sensor messages for better visibility
       - sensor_{accel, gyro}_fifo: full raw data for optional logging and analysis
       - sensor_{accel, gyro}_status: metadata, clipping, etc
       - sensor_{accel, gyro}_integrated: delta angles and delta velocities
       - eventually these will replace the existing sensor_{accel, gyro} monolith
  • Loading branch information
dagar committed Oct 22, 2019
1 parent 35398e0 commit 4bbf41c
Show file tree
Hide file tree
Showing 94 changed files with 4,861 additions and 149 deletions.
1 change: 1 addition & 0 deletions boards/modalai/fc-v1/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ px4_add_board(
imu/bmi088
# TODO imu/icm42688
imu/mpu6000
imu/invensense/icm20602
irlock
lights/blinkm
lights/rgbled
Expand Down
2 changes: 1 addition & 1 deletion boards/modalai/fc-v1/init/rc.board_sensors
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
voxlpm -R start

# Internal SPI bus ICM-20602
mpu6000 -R 2 -s -T 20602 start
icm20602 start -R 2

# Internal SPI bus ICM-42688
# TODO
Expand Down
3 changes: 3 additions & 0 deletions boards/modalai/fc-v1/nuttx-config/include/board.h
Original file line number Diff line number Diff line change
Expand Up @@ -391,6 +391,9 @@
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_2 /* PB5 */
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 /* PA5 */

#define DMAMAP_SPI1_RX DMAMAP_SPI1_RX_1
#define DMAMAP_SPI1_TX DMAMAP_SPI1_TX_2

#define GPIO_SPI2_MISO GPIO_SPI2_MISO_3 /* PI2 */
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_3 /* PI3 */
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_5 /* PI1 */
Expand Down
10 changes: 5 additions & 5 deletions boards/modalai/fc-v1/nuttx-config/nsh/defconfig
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ CONFIG_MTD=y
CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_RAMTRON=y
CONFIG_NFILE_DESCRIPTORS=54
CONFIG_NFILE_DESCRIPTORS=20
CONFIG_NFILE_STREAMS=8
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARCHROMFS=y
Expand Down Expand Up @@ -139,11 +139,11 @@ CONFIG_RTC_DATETIME=y
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1024
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1280
CONFIG_SCHED_LPWORKSTACKSIZE=1536
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SEM_NNESTPRIO=8
Expand Down Expand Up @@ -185,11 +185,11 @@ CONFIG_STM32F7_SDMMC_DMA=y
CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32F7_SPI1=y
CONFIG_STM32F7_SPI1_DMA=y
CONFIG_STM32F7_SPI2=y
CONFIG_STM32F7_SPI3=n
CONFIG_STM32F7_SPI4=n
CONFIG_STM32F7_SPI5=y
CONFIG_STM32F7_SPI6=y
CONFIG_STM32F7_SPI_DMA=y
CONFIG_STM32F7_TIM10=y
CONFIG_STM32F7_TIM11=y
CONFIG_STM32F7_TIM3=y
Expand Down
5 changes: 0 additions & 5 deletions boards/modalai/fc-v1/src/spi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -332,9 +332,7 @@ __EXPORT void board_spi_reset(int mask_ms)
stm32_configgpio(GPIO_SPI1_SCK_OFF);
stm32_configgpio(GPIO_SPI1_MISO_OFF);
stm32_configgpio(GPIO_SPI1_MOSI_OFF);
#if BOARD_USE_DRDY
stm32_configgpio(GPIO_DRDY_OFF_SPI1_DRDY1_ICM20602);
#endif

/* set the sensor rail off */

Expand Down Expand Up @@ -427,10 +425,7 @@ __EXPORT void board_spi_reset(int mask_ms)
stm32_configgpio(GPIO_SPI1_SCK);
stm32_configgpio(GPIO_SPI1_MISO);
stm32_configgpio(GPIO_SPI1_MOSI);
#if BOARD_USE_DRDY
stm32_configgpio(GPIO_SPI1_DRDY1_ICM20602);
#endif

}

#endif
Expand Down
1 change: 1 addition & 0 deletions boards/mro/ctrl-zero-f7/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ px4_add_board(
#imu/bmi088
imu/mpu6000
imu/icm20948
imu/invensense/icm20602
irlock
#lights/blinkm
lights/rgbled
Expand Down
2 changes: 1 addition & 1 deletion boards/mro/ctrl-zero-f7/init/rc.board_sensors
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
#------------------------------------------------------------------------------

# Internal ICM-20602
mpu6000 -R 10 -s -T 20602 start
icm20602 -R 10 start

# Internal ICM-20689
#icm20689 -R 10 20689 start
Expand Down
4 changes: 4 additions & 0 deletions boards/mro/ctrl-zero-f7/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,10 @@
#define GPIO_SPI1_CS1_ICM20602 /* PC2 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
#define GPIO_SPI1_CS2_ICM20948 /* PE15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN15)

/* Define the SPI1 Data Ready interrupts */
#define GPIO_SPI1_DRDY1_ICM20602 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15)
#define GPIO_SPI1_DRDY2_ICM20948 /* PE12 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTE|GPIO_PIN12)

/* SPI 2 CS */
#define GPIO_SPI2_CS1_FRAM /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
#define GPIO_SPI2_CS2_BARO /* PD7 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
Expand Down
7 changes: 7 additions & 0 deletions boards/mro/ctrl-zero-f7/src/spi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -204,6 +204,9 @@ __EXPORT void board_spi_reset(int ms)
stm32_configgpio(_PIN_OFF(GPIO_SPI1_MISO));
stm32_configgpio(_PIN_OFF(GPIO_SPI1_MOSI));

stm32_configgpio(_PIN_OFF(GPIO_SPI1_DRDY1_ICM20602));
stm32_configgpio(_PIN_OFF(GPIO_SPI1_DRDY2_ICM20948));

// SPI5
for (auto cs : spi5selects_gpio) {
stm32_configgpio(_PIN_OFF(cs));
Expand Down Expand Up @@ -243,6 +246,10 @@ __EXPORT void board_spi_reset(int ms)
stm32_configgpio(GPIO_SPI1_MISO);
stm32_configgpio(GPIO_SPI1_MOSI);

stm32_configgpio(GPIO_SPI1_DRDY1_ICM20602);
stm32_configgpio(GPIO_SPI1_DRDY2_ICM20948);


// SPI5
for (auto cs : spi5selects_gpio) {
stm32_configgpio(cs);
Expand Down
5 changes: 4 additions & 1 deletion boards/px4/fmu-v4/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,10 @@ px4_add_board(
dshot
gps
heater
imu # all available imu drivers
#imu # all available imu drivers
imu/invensense/icm20602
imu/invensense/icm20608-g
imu/invensense/mpu9250
irlock
lights/blinkm
lights/rgbled
Expand Down
4 changes: 2 additions & 2 deletions boards/px4/fmu-v4/init/rc.board_sensors
Original file line number Diff line number Diff line change
Expand Up @@ -48,10 +48,10 @@ fi
# will prevent the incorrect driver from a successful initialization.

# ICM20602 internal SPI bus ICM-20608-G is rotated 90 deg yaw
if ! mpu6000 -R 2 -T 20602 start
if ! icm20602 -R 8 start
then
# ICM20608 internal SPI bus ICM-20602-G is rotated 90 deg yaw
if ! mpu6000 -R 2 -T 20608 start
if ! icm20608g -R 8 start
then
# BMI055 accel internal SPI bus
bmi055 -A start
Expand Down
4 changes: 4 additions & 0 deletions boards/px4/fmu-v4/nuttx-config/include/board.h
Original file line number Diff line number Diff line change
Expand Up @@ -269,6 +269,10 @@
#define GPIO_SPI1_MOSI (GPIO_SPI1_MOSI_1|GPIO_SPEED_50MHz)
#define GPIO_SPI1_SCK (GPIO_SPI1_SCK_1|GPIO_SPEED_50MHz)

#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1
#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_2


#define GPIO_SPI2_MISO (GPIO_SPI2_MISO_1|GPIO_SPEED_50MHz)
#define GPIO_SPI2_MOSI (GPIO_SPI2_MOSI_1|GPIO_SPEED_50MHz)
#define GPIO_SPI2_SCK (GPIO_SPI2_SCK_1|GPIO_SPEED_50MHz)
Expand Down
2 changes: 2 additions & 0 deletions boards/px4/fmu-v4/nuttx-config/nsh/defconfig
Original file line number Diff line number Diff line change
Expand Up @@ -184,8 +184,10 @@ 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_SPI_DMA=y
CONFIG_STM32_TIM10=y
CONFIG_STM32_TIM11=y
CONFIG_STM32_TIM1=y
Expand Down
9 changes: 9 additions & 0 deletions boards/px4/fmu-v4/nuttx-config/stackcheck/defconfig
Original file line number Diff line number Diff line change
@@ -1,3 +1,10 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DISABLE_OS_API is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
Expand Down Expand Up @@ -178,8 +185,10 @@ 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_SPI_DMA=y
CONFIG_STM32_TIM10=y
CONFIG_STM32_TIM11=y
CONFIG_STM32_TIM1=y
Expand Down
4 changes: 2 additions & 2 deletions boards/px4/fmu-v4/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,7 @@
/* Use these in place of the uint32_t enumeration to select a specific SPI device on SPI1 */
#define PX4_SPIDEV_GYRO PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 1)
#define PX4_SPIDEV_ACCEL_MAG PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 2)
#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 4)
#define PX4_SPIDEV_MPU9250 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 4)
#define PX4_SPIDEV_HMC PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 5)
#define PX4_SPIDEV_ICM PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 6)
#define PX4_SPIDEV_LIS PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 7)
Expand Down Expand Up @@ -352,7 +352,7 @@
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS

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

#define BOARD_HAS_ON_RESET 1

Expand Down
2 changes: 1 addition & 1 deletion boards/px4/fmu-v4/src/init.c
Original file line number Diff line number Diff line change
Expand Up @@ -326,7 +326,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
SPI_SETMODE(spi1, SPIDEV_MODE3);
SPI_SELECT(spi1, PX4_SPIDEV_GYRO, false);
SPI_SELECT(spi1, PX4_SPIDEV_HMC, false);
SPI_SELECT(spi1, PX4_SPIDEV_MPU, false);
SPI_SELECT(spi1, PX4_SPIDEV_MPU9250, false);
up_udelay(20);

// Get the SPI port for the FRAM.
Expand Down
2 changes: 1 addition & 1 deletion boards/px4/fmu-v4/src/spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool s
/* Shared PC2 CS devices */

case PX4_SPIDEV_BMI:
case PX4_SPIDEV_MPU:
case PX4_SPIDEV_MPU9250:
/* Making sure the other peripherals are not selected */
px4_arch_gpiowrite(GPIO_SPI1_CS_PORTC_PIN2, !selected);
px4_arch_gpiowrite(GPIO_SPI1_CS_PORTC_PIN15, 1);
Expand Down
2 changes: 1 addition & 1 deletion boards/px4/fmu-v4/src/timer_config.c
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
* Copyright (C) 2019 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
Expand Down
5 changes: 3 additions & 2 deletions boards/px4/fmu-v4pro/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,9 @@ px4_add_board(
imu/bma180
imu/bmi160
imu/l3gd20
imu/mpu6000
imu/mpu9250
imu/invensense/mpu9250
imu/invensense/icm20602
imu/invensense/icm20608-g
irlock
lights/blinkm
lights/rgbled
Expand Down
4 changes: 2 additions & 2 deletions boards/px4/fmu-v4pro/init/rc.board_sensors
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@
#------------------------------------------------------------------------------

# Internal SPI bus ICM-20608-G
mpu6000 -R 2 -T 20608 start
icm20608g start

# Internal SPI bus ICM-20602
mpu6000 -R 2 -T 20602 start
icm20602 start

# Internal SPI bus mpu9250
mpu9250 -R 2 start
Expand Down
2 changes: 2 additions & 0 deletions boards/px4/fmu-v4pro/nuttx-config/include/board.h
Original file line number Diff line number Diff line change
Expand Up @@ -383,6 +383,8 @@
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1

#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1
#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_2

#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1
Expand Down
2 changes: 2 additions & 0 deletions boards/px4/fmu-v4pro/nuttx-config/nsh/defconfig
Original file line number Diff line number Diff line change
Expand Up @@ -188,9 +188,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_SPI5=y
CONFIG_STM32_SPI6=y
CONFIG_STM32_SPI_DMA=y
CONFIG_STM32_TIM10=y
CONFIG_STM32_TIM11=y
CONFIG_STM32_TIM1=y
Expand Down
2 changes: 1 addition & 1 deletion boards/px4/fmu-v4pro/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -165,7 +165,7 @@
#define PX4_SPIDEV_GYRO PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 1)
#define PX4_SPIDEV_ACCEL_MAG PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 2)
#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 3)
#define PX4_SPIDEV_MPU PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 4)
#define PX4_SPIDEV_MPU9250 PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 4)
#define PX4_SPIDEV_HMC PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 5)
#define PX4_SPIDEV_ICM PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 6)
#define PX4_SPIDEV_LIS PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 7)
Expand Down
2 changes: 1 addition & 1 deletion boards/px4/fmu-v4pro/src/init.c
Original file line number Diff line number Diff line change
Expand Up @@ -335,7 +335,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
SPI_SELECT(spi1, PX4_SPIDEV_ICM, false);
SPI_SELECT(spi1, PX4_SPIDEV_BARO, false);
SPI_SELECT(spi1, PX4_SPIDEV_LIS, false);
SPI_SELECT(spi1, PX4_SPIDEV_MPU, false);
SPI_SELECT(spi1, PX4_SPIDEV_MPU9250, false);
SPI_SELECT(spi1, PX4_SPIDEV_EEPROM, false);
up_udelay(20);

Expand Down
2 changes: 1 addition & 1 deletion boards/px4/fmu-v4pro/src/spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool s
stm32_gpiowrite(GPIO_SPI_CS_TEMPCAL_EEPROM, 1);
break;

case PX4_SPIDEV_MPU:
case PX4_SPIDEV_MPU9250:
/* Making sure the other peripherals are not selected */
stm32_gpiowrite(GPIO_SPI_CS_MPU9250, !selected);
stm32_gpiowrite(GPIO_SPI_CS_LIS3MDL, 1);
Expand Down
4 changes: 3 additions & 1 deletion boards/px4/fmu-v5/critmonitor.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -25,14 +25,16 @@ px4_add_board(
camera_trigger
differential_pressure # all available differential pressure drivers
distance_sensor # all available distance sensor drivers
dshot
gps
#heater
imu/adis16448
imu/adis16497
#imu # all available imu drivers
imu/bmi055
imu/mpu6000
imu/mpu9250
imu/invensense/icm20602
imu/invensense/icm20689
irlock
lights/blinkm
lights/rgbled
Expand Down
3 changes: 2 additions & 1 deletion boards/px4/fmu-v5/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,9 @@ px4_add_board(
imu/adis16497
#imu # all available imu drivers
imu/bmi055
imu/mpu6000
imu/mpu9250
imu/invensense/icm20602
imu/invensense/icm20689
irlock
lights/blinkm
lights/rgbled
Expand Down
4 changes: 3 additions & 1 deletion boards/px4/fmu-v5/fixedwing.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,8 @@ px4_add_board(
gps
imu/adis16448
imu/bmi055
imu/mpu6000
imu/invensense/icm20602
imu/invensense/icm20689
lights/rgbled
lights/rgbled_ncp5623c
lights/rgbled_pwm
Expand Down Expand Up @@ -63,6 +64,7 @@ px4_add_board(
SYSTEMCMDS
bl_update
config
dmesg
dumpfile
esc_calib
hardfault_log
Expand Down
4 changes: 2 additions & 2 deletions boards/px4/fmu-v5/init/rc.board_sensors
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@
#------------------------------------------------------------------------------

# Internal SPI bus ICM-20602
mpu6000 -R 8 -s -T 20602 start
icm20602 -R 2 start

# Internal SPI bus ICM-20689
mpu6000 -R 8 -z -T 20689 start
icm20689 -R 2 start

# Internal SPI bus BMI055 accel
bmi055 -A -R 10 start
Expand Down
4 changes: 3 additions & 1 deletion boards/px4/fmu-v5/irqmonitor.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -25,14 +25,16 @@ px4_add_board(
camera_trigger
differential_pressure # all available differential pressure drivers
distance_sensor # all available distance sensor drivers
dshot
gps
#heater
imu/adis16448
imu/adis16497
#imu # all available imu drivers
imu/bmi055
imu/mpu6000
imu/mpu9250
imu/invensense/icm20602
imu/invensense/icm20689
irlock
lights/blinkm
lights/rgbled
Expand Down
Loading

0 comments on commit 4bbf41c

Please sign in to comment.