Skip to content

[crash][AP_HAL_ESP32] when ICM20948 is defined #31234

@akhodeir

Description

@akhodeir

Issue details
I modified esp32s3devkit board to use ICM20948 instead of MPU9250.
The system starts to crash.

here is how I defined my definition for ICM20948 :

  In libraries/AP_HAL_ESP32/boards/esp32s3devkit.h:

  // ICM20948 via SPI configuration
  #define HAL_INS_DEFAULT HAL_INS_ICM20XXX_SPI
  #define HAL_INS_ICM20948_NAME "icm20948"

  // Enable ICM20948 compass support
  #define AP_COMPASS_ICM20948_ENABLED 1
  #define AP_COMPASS_AK09916_ENABLED 1

  // Compass: AK09916 integrated in ICM20948
  #define HAL_COMPASS_MAX_SENSORS 3

  // IMU probing: ICM20948 via SPI
  #define HAL_INS_PROBE_LIST PROBE_IMU_SPI(Invensensev2, HAL_INS_ICM20948_NAME, ROTATION_NONE)

  // MAG/COMPASS probing: AK09916 inside ICM20948 via SPI
  // Use direct ADD_BACKEND instead of PROBE_MAG_IMU macro
  #define HAL_MAG_PROBE_LIST ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(0, ROTATION_NONE))

  // SPI device configuration
  #define HAL_ESP32_SPI_DEVICES \
      {.name="icm20948", .bus=0, .device=0, .cs=GPIO_NUM_13, .mode=0, .lspeed=8*MHZ, .hspeed=8*MHZ}

  // Disable external I2C compass probing to avoid conflicts
  #define HAL_PROBE_EXTERNAL_I2C_COMPASSES 0

this is the assert :
assert failed: rmt_ll_rx_set_carrier_high_low_ticks /IDF/components/hal/esp32s3/include/hal/rmt_ll.h:661 (high_ticks >= 1 && high_ticks <= 65536 && low_ticks >= 1 && low_ticks <= 65536 && "out of ran

after figuring out the issue :

xtensa-esp32s3-elf-addr2line -pfC -e build/esp32s3devkit/esp-idf_build/ardupilot.elf 0x4037cae6:0x3fccc070 0x40384afd:0x3fccc090 0x4038d4a1:0x3fccc0b0 0x420f091b:0x3fccc1d0 0x420dd309:0x3fccc250 0x420dcafa:0x3fccc2a0 0x4037a971:0x3fccc2c0
panic_abort at /opt/esp/idf/components/esp_system/panic.c:478
esp_system_abort at /opt/esp/idf/components/esp_system/port/esp_system_chip.c:87
__assert_func at /opt/esp/idf/components/newlib/assert.c:80
rmt_ll_rx_set_carrier_high_low_ticks at /opt/esp/idf/components/hal/esp32s3/include/hal/rmt_ll.h:661 (discriminator 3)
ESP32::RmtSigReader::init() at /ardupilot/build/esp32s3devkit/../../libraries/AP_HAL_ESP32/RmtSigReader.cpp:21
ESP32::RCInput::init() at /ardupilot/build/esp32s3devkit/../../libraries/AP_HAL_ESP32/RCInput.cpp:39


Version
What version was the issue encountered with

Platform
[ ] All
[ ] AntennaTracker
[ x ] Copter
[ ] Plane
[ ] Rover
[ ] Submarine

Airframe type
Quad

Hardware type

I only have ICM20948 via SPI to ESP32S3

Logs

here is my board :


#pragma once

#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_ESP32_S3DEVKIT
// make sensor selection clearer
#define PROBE_IMU_I2C(driver, bus, addr, args ...) ADD_BACKEND(AP_InertialSensor_ ## driver::probe(*this,GET_I2C_DEVICE(bus, addr),##args))
#define PROBE_IMU_SPI(driver, devname, args ...) ADD_BACKEND(AP_InertialSensor_ ## driver::probe(*this,hal.spi->get_device(devname),##args))
#define PROBE_IMU_SPI2(driver, devname1, devname2, args ...) ADD_BACKEND(AP_InertialSensor_ ## driver::probe(*this,hal.spi->get_device(devname1),hal.spi->get_device(devname2),##args))

#define PROBE_BARO_I2C(driver, bus, addr, args ...) ADD_BACKEND(AP_Baro_ ## driver::probe(*this,std::move(GET_I2C_DEVICE(bus, addr)),##args))
#define PROBE_BARO_SPI(driver, devname, args ...) ADD_BACKEND(AP_Baro_ ## driver::probe(*this,std::move(hal.spi->get_device(devname)),##args))

#define PROBE_MAG_I2C(driver, bus, addr, args ...) ADD_BACKEND(DRIVER_ ##driver, AP_Compass_ ## driver::probe(GET_I2C_DEVICE(bus, addr),##args))
#define PROBE_MAG_SPI(driver, devname, args ...) ADD_BACKEND(DRIVER_ ##driver, AP_Compass_ ## driver::probe(hal.spi->get_device(devname),##args))
#define PROBE_MAG_IMU(driver, imudev, imu_instance, args ...) ADD_BACKEND(DRIVER_ ##driver, AP_Compass_ ## driver::probe_ ## imudev(imu_instance,##args))
#define PROBE_MAG_IMU_I2C(driver, imudev, bus, addr, args ...) ADD_BACKEND(DRIVER_ ##driver, AP_Compass_ ## driver::probe_ ## imudev(GET_I2C_DEVICE(bus,addr),##args))

//- these are missing from esp-idf......will not be needed later
#define RTC_WDT_STG_SEL_OFF             0
#define RTC_WDT_STG_SEL_INT             1
#define RTC_WDT_STG_SEL_RESET_CPU       2
#define RTC_WDT_STG_SEL_RESET_SYSTEM    3
#define RTC_WDT_STG_SEL_RESET_RTC       4

#define HAL_ESP32_BOARD_NAME "esp32s3devkit"

#define HAL_ESP32_RMT_RX_PIN_NUMBER GPIO_NUM_14

//#define CONFIG_HAL_BOARD 12
//#define HAL_BOARD_ESP32 12
#define AP_INERTIALSENSOR_ENABLED 1

// ICM20948 via SPI configuration
#define HAL_INS_DEFAULT HAL_INS_ICM20XXX_SPI
#define HAL_INS_ICM20948_NAME "icm20948"

// Enable ICM20948 compass support
#define AP_COMPASS_ICM20948_ENABLED 1
#define AP_COMPASS_AK09916_ENABLED 1

// Compass: AK09916 integrated in ICM20948
#define HAL_COMPASS_MAX_SENSORS 3

// IMU probing: ICM20948 via SPI
#define HAL_INS_PROBE_LIST PROBE_IMU_SPI(Invensensev2, HAL_INS_ICM20948_NAME, ROTATION_NONE)

// MAG/COMPASS probing: AK09916 inside ICM20948 via SPI
#define HAL_MAG_PROBE_LIST ADD_BACKEND(DRIVER_ICM20948, AP_Compass_AK09916::probe_ICM20948(0, ROTATION_NONE))
// BARO probing:
#define HAL_BARO_PROBE_LIST PROBE_BARO_I2C(BMP280, 0, 0x77)

// allow boot without a baro
#define HAL_BARO_ALLOW_INIT_NO_BARO 1


// ADC is available on lots of pints on the esp32, but adc2 cant co-exist with wifi we choose to allow ADC on :
//#define HAL_DISABLE_ADC_DRIVER 1
#define TRUE 1
#define HAL_USE_ADC TRUE

// the pin number, the gain/multiplier associated with it, the ardupilot name for the pin in parameter/s.
//
// two different pin numbering schemes, both are ok, but only one at a time:
#define HAL_ESP32_ADC_PINS_OPTION1 {\
	{ADC_CHANNEL_4, 11, 1},\
	{ADC_CHANNEL_3, 11, 2},\
	{ADC_CHANNEL_1, 11, 3},\
	{ADC_CHANNEL_0, 11, 4}\
}
#define HAL_ESP32_ADC_PINS_OPTION2 {\
	{ADC_GPIO35_CHANNEL, 11, 35},\
	{ADC_GPIO34_CHANNEL, 11, 34},\
	{ADC_GPIO39_CHANNEL, 11, 39},\
	{ADC_GPIO36_CHANNEL, 11, 36}\
}
// pick one:
//#define HAL_ESP32_ADC_PINS HAL_ESP32_ADC_PINS_OPTION1
#define HAL_ESP32_ADC_PINS HAL_ESP32_ADC_PINS_OPTION1

#define HAL_INS_ICM20948_NAME "icm20948"

// uncommenting one or more of these will give more console debug in certain areas..
//#define INSEDEBUG 1
//#define STORAGEDEBUG 1
//#define SCHEDDEBUG 1
//#define FSDEBUG 1
//#define BUSDEBUG 1

// Disable external I2C compass probing to avoid conflicts with ICM20948's internal compass
#define HAL_PROBE_EXTERNAL_I2C_COMPASSES 0

//#define HAL_BARO_PROBE_LIST PROBE_BARO_SPI(BMP280, "bmp280")

// 2 use udp, 1 use tcp...  for udp,client needs to connect as UDPCL in missionplanner etc to 192.168.4.1 port 14550
#define HAL_ESP32_WIFI 2

// tip: if u are ok getting mavlink-over-tcp or mavlink-over-udp and want to disable mavlink-over-serial-usb
//then set ardupilot parameter SERIAL0_PROTOCOL = 0 and reboot.
// u also will/may want..
//LOG_BACKEND_TYPE 1
//LOG_DISARMED 1
//SERIAL0_PROTOCOL 0

// Configure as WiFi Station (client) instead of Access Point
#define WIFI_STATION 1
#define WIFI_SSID_STATION "ABC"
#define WIFI_PWD "12345678"
#define WIFI_HOSTNAME "ArduPilot-ESP32S3"
// UDP destination IP for MAVLink forwarding
#define WIFI_UDP_DEST_IP "192.168.178.20"

//RCOUT which pins are used?

#define HAL_ESP32_RCOUT { GPIO_NUM_9,GPIO_NUM_8, GPIO_NUM_6, GPIO_NUM_6, GPIO_NUM_5, GPIO_NUM_4 }

// SPI BUS setup, including gpio, dma, etc
// SPI3 (VSPI) used for ICM20948 IMU
#define HAL_ESP32_SPI_BUSES \
    {.host=SPI3_HOST, .dma_ch=SPI_DMA_CH_AUTO, .mosi=GPIO_NUM_11, .miso=GPIO_NUM_12, .sclk=GPIO_NUM_10}
// tip:  VSPI_HOST  is an alternative name for esp's SPI3
//#define HAL_ESP32_SPI_BUSES {}

// SPI per-device setup, including speeds, etc.
// ICM20948: CS=GPIO13, SCK=GPIO10, MOSI=GPIO11, MISO=GPIO12
#define HAL_ESP32_SPI_DEVICES \
    {.name="icm20948", .bus=0, .device=0, .cs=GPIO_NUM_13,  .mode = 0, .lspeed=2*MHZ, .hspeed=8*MHZ}
//#define HAL_ESP32_SPI_DEVICES {}

//I2C bus list
#define HAL_ESP32_I2C_BUSES \
	{.port=I2C_NUM_0, .sda=GPIO_NUM_16, .scl=GPIO_NUM_15, .speed=400*KHZ, .internal=true}
//#define HAL_ESP32_I2C_BUSES {} // using this embty block appears to cause crashes?


// rcin on what pin?
#define HAL_ESP32_RCIN GPIO_NUM_14


//HARDWARE UARTS
#define HAL_ESP32_UART_DEVICES \
  {.port=UART_NUM_0, .rx=GPIO_NUM_44, .tx=GPIO_NUM_43 },{.port=UART_NUM_1, .rx=GPIO_NUM_17, .tx=GPIO_NUM_18 }

// Filesystem and SD card completely disabled to avoid GPIO conflicts
#define HAVE_FILESYSTEM_SUPPORT 0

// Do u want to use mmc or spi mode for the sd card, this is board specific ,
//  as mmc uses specific pins but is quicker,
#define HAL_ESP32_SDMMC 0
// and spi is more flexible pinouts....  dont forget vspi/hspi should be selected to NOT conflict with SPI_BUSES above
//#define HAL_ESP32_SDSPI {.host=VSPI_HOST, .dma_ch=2, .mosi=GPIO_NUM_2, .miso=GPIO_NUM_15, .sclk=GPIO_NUM_14, .cs=GPIO_NUM_21}

#define HAL_ESP32_SDCARD 0
#define LOGGER_MAVLINK_SUPPORT 1
#define HAL_OS_POSIX_IO 1

// this becomes the default value for the ardupilot param LOG_BACKEND_TYPE, which most ppl want to be 1, for log-to-flash
// setting to 2 means log-over-mavlink to a companion computer etc.
#define HAL_LOGGING_BACKENDS_DEFAULT 1


Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions