Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ICM426XX - Disable AFSR #933

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 13 additions & 1 deletion src/main/drivers/accgyro/accgyro_spi_icm426xx.c
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,11 @@
#define ICM426XX_BANK_SELECT3 0x03
#define ICM426XX_BANK_SELECT4 0x04

// Fix for stalls in gyro output. See https://github.com/ArduPilot/ardupilot/pull/25332 ; https://github.com/betaflight/betaflight/pull/13132
#define ICM426XX_INTF_CONFIG1 0x4D
#define ICM426XX_INTF_CONFIG1_AFSR_MASK 0xC0
#define ICM426XX_INTF_CONFIG1_AFSR_DISABLE 0x40

#define ICM426XX_RA_PWR_MGMT0 0x4E // User Bank 0
#define ICM426XX_PWR_MGMT0_ACCEL_MODE_LN (3 << 0)
#define ICM426XX_PWR_MGMT0_GYRO_MODE_LN (3 << 2)
Expand Down Expand Up @@ -284,13 +289,20 @@ void icm426xxGyroInit(gyroDev_t *gyro)

spiBusWriteRegister(&gyro->bus, ICM426XX_RA_INT_SOURCE0, ICM426XX_UI_DRDY_INT1_EN_ENABLED);

uint8_t intConfig1Value = spiReadRegMsk(&gyro->bus, ICM426XX_RA_INT_CONFIG1);
uint8_t intConfig1Value = spiBusReadRegister(&gyro->bus, ICM426XX_RA_INT_CONFIG1);
// Datasheet says: "User should change setting to 0 from default setting of 1, for proper INT1 and INT2 pin operation"
intConfig1Value &= ~(1 << ICM426XX_INT_ASYNC_RESET_BIT);
intConfig1Value |= (ICM426XX_INT_TPULSE_DURATION_8 | ICM426XX_INT_TDEASSERT_DISABLED);

spiBusWriteRegister(&gyro->bus, ICM426XX_RA_INT_CONFIG1, intConfig1Value);

// Disable AFSR to prevent stalls in gyro output
// ICM426XX_INTF_CONFIG1 location in user bank 0
uint8_t intfConfig1Value = spiBusReadRegister(&gyro->bus, ICM426XX_INTF_CONFIG1);
intfConfig1Value &= ~ICM426XX_INTF_CONFIG1_AFSR_MASK;
intfConfig1Value |= ICM426XX_INTF_CONFIG1_AFSR_DISABLE;
spiBusWriteRegister(&gyro->bus, ICM426XX_INTF_CONFIG1, intfConfig1Value);

// Turn on gyro and acc on again so ODR and FSR can be configured
turnGyroAccOn(gyro);

Expand Down
3 changes: 2 additions & 1 deletion src/main/drivers/bus_spi.c
Original file line number Diff line number Diff line change
Expand Up @@ -272,7 +272,8 @@ uint16_t spiCalculateDivider(uint32_t freq)
return divisor;
}

// Wait for bus to become free, then read a byte of data where the register is ORed with 0x80
// Wait for bus to become free, then read a byte of data where the register is bitwise OR'ed with 0x80
// EmuFlight codebase is old. Bitwise or 0x80 is redundant here as spiBusReadRegister already contains such.
uint8_t spiReadRegMsk(const busDevice_t *bus, uint8_t reg)
{
return spiBusReadRegister(bus, reg | 0x80);
Expand Down
Loading