From 9c5b6d4211491adbf3e41d318d1d36a6902ae62c Mon Sep 17 00:00:00 2001 From: jeetrohan Date: Tue, 22 Oct 2024 22:37:22 +0530 Subject: [PATCH 1/9] mpu60xx.h header file for mpu60xx driver --- components/mpu60xx/include/mpu60xx.h | 336 +++++++++++++++++++++++++++ 1 file changed, 336 insertions(+) create mode 100644 components/mpu60xx/include/mpu60xx.h diff --git a/components/mpu60xx/include/mpu60xx.h b/components/mpu60xx/include/mpu60xx.h new file mode 100644 index 00000000..39ac6991 --- /dev/null +++ b/components/mpu60xx/include/mpu60xx.h @@ -0,0 +1,336 @@ +/* + * mpu60xx.h + * + * Created on: 15-Oct-2024 + * Author: rohan + */ + +#ifndef __MPU_60XX_H +#define __MPU_60XX_H + + +#include +#include +#include +#include + +#include "esp_log.h" +#include "esp_err.h" + +#include "freertos/FreeRTOS.h" + +#include "driver/gpio.h" +#include "driver/i2c_master.h" + + + +#ifdef __cplusplus +extern "C" { +#endif + + +/** + * @brief Accelerometer range options + *Allowed values for 'setAccelerometerRange'. + */ +typedef enum { + MPU60XX_RANGE_2_G = 0x00, /*!< +/- 2g (default) */ + MPU60XX_RANGE_4_G = 0x08, /*!< +/- 4g */ + MPU60XX_RANGE_8_G = 0x10, /*!< +/- 8g */ + MPU60XX_RANGE_16_G = 0x18, /*!< +/- 16g */ +} mpu60xx_accel_range_t; + +/** + * @brief Gyroscope range options + * Allowed values for 'setGyrometerRange'. + */ +typedef enum { + MPU60XX_RANGE_250_DEG = 0x00, /*< +/- 250 deg/s (default) */ + MPU60XX_RANGE_500_DEG = 0x08, /*< +/- 500 deg/s */ + MPU60XX_RANGE_1000_DEG = 0x10, /*< +/- 1000 deg/s */ + MPU60XX_RANGE_2000_DEG = 0x18, /*< +/- 2000 deg/s */ +} mpu60xx_gyro_range_t; + +/** + * @brief Digital low pass filter cutoff frequencies + * Allowed values for 'en_DLPF'. + */ +typedef enum { + MPU60XX_BAND_260_HZ, /*!< Default */ + MPU60XX_BAND_184_HZ, /*!< 184 Hz */ + MPU60XX_BAND_94_HZ, /*!< 94 Hz */ + MPU60XX_BAND_44_HZ, /*!< 44 Hz */ + MPU60XX_BAND_21_HZ, /*!< 21 Hz */ + MPU60XX_BAND_10_HZ, /*!< 10 Hz */ + MPU60XX_BAND_5_HZ, /*!< 5 Hz */ +} mpu60xx_lowpass_t; + +/** + * @brief High pass filter cutoff frequencies + * Allowed values for 'en_DHPF'. + */ +typedef enum { + MPU60XX_HIGHPASS_DISABLE, /*!< The filter output settles to zero within one sample. This effectively disables the high pass filter.*/ + MPU60XX_HIGHPASS_5_HZ, /*!< 5 Hz */ + MPU60XX_HIGHPASS_2_5_HZ, /*!< 2.5 Hz */ + MPU60XX_HIGHPASS_1_25_HZ, /*!< 1.25 Hz */ + MPU60XX_HIGHPASS_0_63_HZ, /*!< 0.63 Hz */ + MPU60XX_HIGHPASS_UNUSED_1,/*!< Unused value. */ + MPU60XX_HIGHPASS_UNUSED_2,/*!< Unused value. */ + MPU60XX_HIGHPASS_HOLD, /*!< When triggered, the filter holds the present sample. The filter output will be the difference between the input sample and the held sample. */ +} mpu60xx_highpass_t; + +/** + * @brief Interrupt pin active levels on mpu60xx + * Allowed values for 'active_level' in 'mpu60xx_intrpt_config_t'. + */ +typedef enum { + MPU60XX_INTERRUPT_PIN_ACTIVE_HIGH = 0, /*!< The mpu60xx sets its INT pin HIGH on interrupt. */ + MPU60XX_INTERRUPT_PIN_ACTIVE_LOW = 1 /*!< The mpu60xx sets its INT pin LOW on interrupt. */ +} mpu60xx_int_pin_active_level_t; + +/** + * @brief Interrupt pin modes on mpu60xx + * @note Allowed values for 'pin_mode' in 'mpu60xx_intrpt_config_t'. + */ +typedef enum { + MPU60XX_INTERRUPT_PIN_PUSH_PULL = 0, /*!< The mpu60xx configures its INT pin as push-pull. */ + MPU60XX_INTERRUPT_PIN_OPEN_DRAIN = 1 /*!< The mpu60xx configures its INT pin as open drain. */ +} mpu60xx_int_pin_mode_t; + +/** + * @brief Interrupt pulse behavior on mpu60xx + * + * Allowed values for 'interrupt_latch' in 'mpu60xx_intrpt_config_t'. + */ +typedef enum { + MPU60XX_INTERRUPT_LATCH_50US = 0, /*!< The mpu60xx produces a 50 microsecond pulse on interrupt. */ + MPU60XX_INTERRUPT_LATCH_UNTIL_CLEARED = 1 /*!< The mpu60xx latches its INT pin to its active level, until interrupt is cleared. */ +} mpu60xx_int_latch_t; + +/** + * @brief Interrupt clear conditions on mpu60xx + * @note Allowed values for 'interrupt_clear_behavior' in 'mpu60xx_intrpt_config_t'. + */ +typedef enum { + MPU60XX_INTERRUPT_CLEAR_ON_ANY_READ = 0, /*!< INT_STATUS register bits are cleared on any register read. */ + MPU60XX_INTERRUPT_CLEAR_ON_STATUS_READ = 1 /*!< INT_STATUS register bits are cleared only by reading INT_STATUS value. */ +} mpu60xx_int_clear_t; + +/** + * @brief Interrupt configurations for mpu60xx operations + * @note Implemented only for motion detection + */ +typedef struct { + gpio_num_t interrupt_pin; /*!< esp32 GPIO pin connected to MPU60xx INT pin */ + const gpio_isr_t isr; /*!< ISR routine to handle the interrupt */ + mpu60xx_int_pin_active_level_t active_level; /*!< Active level of MPU60xx INT pin */ + mpu60xx_int_pin_mode_t pin_mode; /*!< Push-pull or open drain mode for MPU60xx INT pin */ + mpu60xx_int_latch_t interrupt_latch; /*!< The interrupt pulse behavior of MPU60xx INT pin */ + mpu60xx_int_clear_t interrupt_clear_behavior; /*!< MPU60xx Interrupt status clear behavior */ +} mpu60xx_intrpt_config_t; + +/** + * @brief Motion detection configurations for mpu60xx + */ +typedef struct{ + uint8_t motion_threshold; /*!< Specifies the Motion detection threshold. Unit of 1 LSB = 1mg. */ + uint8_t motion_duration; /*!< Specifies the duration counter threshold. Unit of 1 LSB = 1ms. */ + mpu60xx_highpass_t dhpf_bw; /*!< Cutoff frequency for digital high pass filter. */ +} mpu60xx_motion_detect_config_t; + +/** + * @brief Structure to store raw values read from mpu60xx + */ +typedef struct { + int16_t + temp_raw, /*!< Last reading's temperature raw */ + accX_raw, /*!< Last reading's accelerometer X axis raw */ + accY_raw, /*!< Last reading's accelerometer Y axis raw */ + accZ_raw, /*!< Last reading's accelerometer Z axis raw */ + gyroX_raw, /*!< Last reading's gyro X axis raw */ + gyroY_raw, /*!< Last reading's gyro Y axis raw */ + gyroZ_raw; /*!< Last reading's gyro Z axis raw */ +} mpu60xx_reading_raw_t; + + +/** + * @brief Structure to store float values read from mpu60xx + */ +typedef struct { + float_t + temperature, /*!< Last reading's temperature (°C) */ + accX, /*!< Last reading's accelerometer X axis m/s^2 */ + accY, /*!< Last reading's accelerometer Y axis m/s^2 */ + accZ, /*!< Last reading's accelerometer Z axis m/s^2 */ + gyroX, /*!< Last reading's gyro X axis in degrees/s */ + gyroY, /*!< Last reading's gyro Y axis in degrees/s */ + gyroZ; /*!< Last reading's gyro Z axis in degrees/s */ +} mpu60xx_reading_t; + +/** + * @brief Minimal configurations for mpu60xx operations + */ +typedef struct{ + uint32_t scl_speed_hz; /*!< MPU60xx i2c clock speed. */ + mpu60xx_gyro_range_t gyro_res; /*!< Gyrometer resolution. */ + mpu60xx_accel_range_t accel_res; /*!< Accelerometer resolution. */ + bool temp_sensor; /*!< Enable on-chip temperature sensor. Default is off. */ + mpu60xx_lowpass_t dlpf_bw; /*!< Cutoff frequency for digital low pass filter. */ + uint32_t sample_rate; /*!< Sampling rate. */ +} mpu60xx_init_config_t; + + +/** + * @brief Handle for mpu60xx operations + */ +typedef struct { + i2c_master_bus_handle_t * bus_handle; /*!< i2c bus handle. */ + i2c_master_dev_handle_t * dev_handle; /*!< i2c device handle. */ +}mpu60xx_handle_t; + + +/** + * @brief Set accelerometer resolution + * @note called by "mpu60xx_init",but provided for further flexibility + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init" + * + * @param[in] range Accelerometer range options + * + * @return + * - ESP_OK: accelerometer resolution successfully set + * - other error codes : from the underlying i2c driver, check log + */ +esp_err_t mpu60xx_setAccelerometerRange(mpu60xx_handle_t mpu_handle, mpu60xx_accel_range_t range); + + +/** + * @brief Set gyrometer resolution + * @note called by "mpu60xx_init",but provided for further flexibility + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init" + * + * @param[in] range Gyrometer range options + * + * @return + * - ESP_OK: gyrometer resolution successfully set + * - other error codes : from the underlying i2c driver, check log + * + * + */ +esp_err_t mpu60xx_setGyrometerRange(mpu60xx_handle_t mpu_handle, mpu60xx_gyro_range_t range); + +/** + * @brief Set sampling rate + * @note called by "mpu60xx_init",but provided for further flexibility + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init" + * + * @param[in] sample_rate Sampling rate of mpu60xx + * + * @param[in] dlpf_bw Low pass frequency + * @note using value other than MPU60XX_BAND_260_HZ (default), puts an upper limit of 1KHz on 'sample_rate', + * @note the default behavior allows 'sample_rate' upper limit of + * gyrometer as 8KHz and accelerometer readings as 1KHz. + * Corresponding accelerometer readings are repeated for samples, if 'sample_rate'>1KHz. + * + * @return + * - ESP_OK: sampling rate successfully set + * - other error codes : from the underlying i2c driver, check log + */ +esp_err_t mpu60xx_setSampleRate ( mpu60xx_handle_t mpu_handle, uint32_t sample_rate, mpu60xx_lowpass_t dlpf_bw); + + +/** + * @brief enable motion detection + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init" + * + * @param[in] mdc Configuration for motion detection + * + * @param[in] interrupt_configuration configuration for motion detection interrupt behavior + * @note can be NULL, use "mpu60xx_en_MotionDetection" for polling + * + * @return + * - ESP_OK: successfully read the Interrupt status register + * - other: failed to set value, check log + */ +esp_err_t mpu60xx_en_MotionDetection(mpu60xx_handle_t * mpu_handle,mpu60xx_motion_detect_config_t *mdc, mpu60xx_intrpt_config_t* interrupt_configuration); + +/** + * @brief enable/disable motion detection interrupt generation on MPU60xx. + * @note internally called by mpu60xx_en_MotionDetection but provided for flexibility. + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init". + * + * @param[in] active if 'true' enables interrupt generation, + * if 'false' disables interrupt generation. + * + * @return + * - ESP_OK: successfully read the Interrupt status register. + * - other: failed to set value, check log. + */ +esp_err_t mpu60xx_enMotionDetectInterrupt(mpu60xx_handle_t * mpu_handle, bool active); + +/** + * @brief read motion detect interrupt status + * @note if "MPU60XX_INTERRUPT_LATCH_UNTIL_CLEARED" was used in "mpu60xx_intrpt_config_t" + * this function needs to be called to clear the interrupt flag on mpu60xx, + * otherwise further interrupts will not be notified + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init" + * + * @param[out] status 'true' if motion detected otherwise 'false' + * + * @return + * - ESP_OK: successfully read the Interrupt status register + * - other: failed to read value, check log + */ +esp_err_t mpu60xx_getMotionInterruptStatus(mpu60xx_handle_t mpu_handle, bool * status); + +/** + * @brief initialize MPU60xx and also the handle used to interact with it. + * + * @param[in] config_handle initial configuration of MPU60xx + * + * @param[out] mpu_handle Handle of mpu60xx + * + * @return + * - ESP_OK: successfully read the Interrupt status register + * - other: failed to read value, check log + */ +esp_err_t mpu60xx_init(mpu60xx_init_config_t config_handle, mpu60xx_handle_t mpu_handle); + +/** + * @brief get float values of accelerometer, gyrometer and temperature sensor readings from MPU60xx + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init" + * + * @param[out] sensor_read structure to hold the values read + * + * @return + * - ESP_OK: successfully read the Interrupt status register + * - other: failed to read value, check log + */ +esp_err_t mpu60xx_read_sensor(mpu60xx_handle_t mpu_handle, mpu60xx_reading_t * sensor_read); + +/** + * @brief get raw values of accelerometer, gyrometer and temperature sensor readings from MPU60xx + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init" + * + * @param[out] sensor_raw_read structure to hold the raw values read + * + * @return + * - ESP_OK: successfully read the Interrupt status register + * - other: failed to read value, check log + */ +esp_err_t mpu60xx_read_sensor_raw (mpu60xx_handle_t mpu_handle, mpu60xx_reading_raw_t * sensor_raw_read); + + +#ifdef __cplusplus +} +#endif + +#endif // __MPU_60XX_H From c25ac3c55297fe22c5f61ac0c8e93c711ecb4223 Mon Sep 17 00:00:00 2001 From: jeetrohan Date: Tue, 22 Oct 2024 22:41:27 +0530 Subject: [PATCH 2/9] mpu60xx CMakeLists.txt --- components/mpu60xx/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) create mode 100644 components/mpu60xx/CMakeLists.txt diff --git a/components/mpu60xx/CMakeLists.txt b/components/mpu60xx/CMakeLists.txt new file mode 100644 index 00000000..fb18b60c --- /dev/null +++ b/components/mpu60xx/CMakeLists.txt @@ -0,0 +1,2 @@ +idf_component_register(SRCS "mpu60xx.c" + INCLUDE_DIRS "include") From b3d079a5c3bba67643fd7322dd99e6ea97ea5066 Mon Sep 17 00:00:00 2001 From: jeetrohan Date: Tue, 22 Oct 2024 22:44:06 +0530 Subject: [PATCH 3/9] mpu60xx.c definitions for mpu60xx driver functions --- components/mpu60xx/mpu60xx.c | 617 +++++++++++++++++++++++++++++++++++ 1 file changed, 617 insertions(+) create mode 100644 components/mpu60xx/mpu60xx.c diff --git a/components/mpu60xx/mpu60xx.c b/components/mpu60xx/mpu60xx.c new file mode 100644 index 00000000..d4a7bdee --- /dev/null +++ b/components/mpu60xx/mpu60xx.c @@ -0,0 +1,617 @@ +/* + * mpu60xx.c + * + * Created on: 15-Oct-2024 + * Author: rohan + */ + +#include +#include +#include +#include + +#include "esp_log.h" +#include "esp_err.h" + +#include "freertos/FreeRTOS.h" + +#include "driver/gpio.h" +#include "driver/i2c_master.h" + +#include "mpu60xx.h" + + + + +//MPU60XX registers +#define MPU60xx_ADDR 0x68 // MPU60XX I2C address + +#define MPU60xx_DEVICE_ID_REG 0X75 // Device ID Register + +#define MPU60xx_USER_CTRL_REG 0X6A // User Control Register +#define MPU60xx_PWR_MGMT1_REG 0X6B // Power Management Registers 1 +#define MPU60xx_PWR_MGMT2_REG 0X6C // Power Management Registers 2 + +#define MPU60xx_SMPRT_DIV 0X19 // Sample Rate Divider +#define MPU60xx_CFG_REG 0X1A // Configuration Register +#define MPU60xx_GYRO_CFG_REG 0X1B // Gyroscope Configuration Register +#define MPU60xx_ACCEL_CFG_REG 0X1C // Accelerometer Configuration Register + +#define MPU60xx_MOT_THR 0x1F // Motion detection threshold bits [7:0] +#define MPU60xx_MOT_DUR 0x20 // Duration counter, threshold for motion int. 1 kHz rate, LSB = 1 ms + + +#define MPU60xx_INT_PIN_CONFIG 0X37 // Interrupt/Bypass Setting Register +#define MPU60xx_INT_EN_REG 0X38 // Interrupt Enable Register +#define MPU60xx_INT_STATUS 0x3A // Interrupt status register + +#define MPU60xx_ACCEL_XOUTH_REG 0X3B // Accelerometer X-axis High Byte Register +#define MPU60xx_ACCEL_XOUTL_REG 0X3C // Accelerometer X-axis Low Byte Register +#define MPU60xx_ACCEL_YOUTH_REG 0X3D // Accelerometer Y-axis High Byte Register +#define MPU60xx_ACCEL_YOUTL_REG 0X3E // Accelerometer Y-axis Low Byte Register +#define MPU60xx_ACCEL_ZOUTH_REG 0X3F // Accelerometer Z-axis High Byte Register +#define MPU60xx_ACCEL_ZOUTL_REG 0X40 // Accelerometer Z-axis Low Byte Register + +#define MPU60xx_TEMP_OUTH_REG 0X41 // Temperature Value High Byte Register +#define MPU60xx_TEMP_OUTL_REG 0X42 // Temperature Value Low Byte Register + +#define MPU60xx_GYRO_XOUTH_REG 0X43 // Gyroscope X-axis High Byte Register +#define MPU60xx_GYRO_XOUTL_REG 0X44 // Gyroscope X-axis Low Byte Register +#define MPU60xx_GYRO_YOUTH_REG 0X45 // Gyroscope Y-axis High Byte Register +#define MPU60xx_GYRO_YOUTL_REG 0X46 // Gyroscope Y-axis Low Byte Register +#define MPU60xx_GYRO_ZOUTH_REG 0X47 // Gyroscope Z-axis High Byte Register +#define MPU60xx_GYRO_ZOUTL_REG 0X48 // Gyroscope Z-axis Low Byte Register +#define MPU60xx_SIGNAL_PATH_RESET 0x68 //Signal path reset register + + +static const char *TAG = "MPU60xx"; // tag used in logs + +static const float_t s_g_value = 9.80665; // standard acceleration of gravity, multiplier to convert accelerometer reading to m/s + + +/** + * @brief Write command to MPU60xx. + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init" + * + * @param[in] reg MPU60xx register address to write to. + * + * @param[in] data Data bytes to send to MPU60xx. + * + * @param[in] length Size, in bytes, of data. + * + * @return + * - ESP_OK: gyrometer resolution successfully set + * - other error codes : from the underlying i2c driver, check log + * + * @note only values defined in "mpu60xx_gyro_range_t" are valid + */ +static esp_err_t mpu60xx_write_register(mpu60xx_handle_t mpu_handle, uint8_t reg,const uint8_t* data, size_t length); + +/** + * @brief Read data from MPU60xx + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init" + * + * @param[in] data_addr MPU60xx register address to read from + * + * @param[out] data Data buffer store values read from the MPU60xx. + * + * @param[in] length Size, in bytes, of data. + * + * @return + * - ESP_OK: gyrometer resolution successfully set + * - other error codes : from the underlying i2c driver, check log + * + * @note only values defined in "mpu60xx_gyro_range_t" are valid + */ +static esp_err_t mpu60xx_read_register(mpu60xx_handle_t mpu_handle, const uint8_t data_addr, uint8_t *data, size_t length); + +/** + * @brief Get accelerometer resolution + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init" + * + * @param[out] range resolution read from accelerometer + * + * @return + * - ESP_OK: gyrometer resolution successfully set + * - other error codes : from the underlying i2c driver, check log + */ +static esp_err_t getAccelerometerRange(mpu60xx_handle_t mpu_handle,mpu60xx_accel_range_t * range ); + +/** + * @brief Get gyrometer resolution + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init" + * + * @param[out] range resolution read from gyrometer + * + * @return + * - ESP_OK: gyrometer resolution successfully set + * - other error codes : from the underlying i2c driver, check log + */ +static esp_err_t getGyrometerRange(mpu60xx_handle_t mpu_handle,mpu60xx_gyro_range_t * range ); + +/** + * @brief Enable digital low pass filter on MPU60xx + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init" + * + * @param[in] b_width low pass filter bandwidth options + * + * @return + * - ESP_OK: successfully enabled dlpf with provided b_width + * - other error codes : from the underlying i2c driver, check log + */ +static esp_err_t en_DLPF( mpu60xx_handle_t mpu_handle, mpu60xx_lowpass_t b_width); + +/** + * @brief Enable digital high pass filter on MPU60xx + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init" + * + * @param[in] b_width high pass filter bandwidth options + * + * @return + * - ESP_OK: successfully enabled dhpf with provided b_width + * - other error codes : from the underlying i2c driver, check log + */ +static esp_err_t en_DHPF( mpu60xx_handle_t mpu_handle, mpu60xx_highpass_t bandwidth); + +/** + * @brief Register ISR to handle interrupt from MPU60xx + * + * @param[in] mpu_handle Handle of mpu60xx initialized by calling "mpu60xx_init" + * + * @param[in] interrupt_configuration configuration passed through "mpu60xx_intrpt_config_t" + * + * @return + * - ESP_OK: successfully registered ISR + * - other error codes : from the underlying i2c driver or ISR mechanism, check log + */ +static esp_err_t register_isr(mpu60xx_handle_t * sensor, mpu60xx_intrpt_config_t* interrupt_configuration); + + + + +static esp_err_t mpu60xx_write_register(mpu60xx_handle_t mpu_handle, uint8_t reg,const uint8_t* data, size_t length) +{ + esp_err_t ret =i2c_master_probe(*mpu_handle.bus_handle, MPU60xx_ADDR, 50); + if (ret == ESP_OK) { + ret=i2c_master_transmit(*mpu_handle.dev_handle, data, length, 50); + } + else + ESP_LOGE(TAG, "mpu60xx not detected on i2c"); + + return ret; +} + +static esp_err_t mpu60xx_read_register(mpu60xx_handle_t mpu_handle, const uint8_t data_addr, uint8_t *data, size_t length) +{ + esp_err_t ret =i2c_master_probe(*mpu_handle.bus_handle, MPU60xx_ADDR, 50); + if (ret == ESP_OK) { + ret = i2c_master_transmit_receive(*mpu_handle.dev_handle, (uint8_t*)&data_addr, 1, data, length,50); + } + else + ESP_LOGE(TAG, "mpu60xx not detected on i2c"); + + return ret; +} + +esp_err_t mpu60xx_setAccelerometerRange(mpu60xx_handle_t mpu_handle, mpu60xx_accel_range_t range) +{ + uint8_t cmd[2]; + cmd[0]=MPU60xx_ACCEL_CFG_REG; + cmd[1]=range; + esp_err_t ret = mpu60xx_write_register(mpu_handle,MPU60xx_ADDR,cmd, 2); + return ret; +} + +static esp_err_t getAccelerometerRange(mpu60xx_handle_t mpu_handle,mpu60xx_accel_range_t * range ) +{ + uint8_t reg_value; + + esp_err_t ret = mpu60xx_read_register(mpu_handle,MPU60xx_ACCEL_CFG_REG, ®_value, 1); + + if (ret == ESP_OK) { + *range = reg_value & 0x18; + } + return ret; +} + +esp_err_t mpu60xx_setGyrometerRange(mpu60xx_handle_t mpu_handle, mpu60xx_gyro_range_t range) +{ + uint8_t cmd[2]; + cmd[0]=MPU60xx_GYRO_CFG_REG; + cmd[1]=range; + esp_err_t ret = mpu60xx_write_register(mpu_handle,MPU60xx_ADDR,cmd, 2); + return ret; +} + +static esp_err_t getGyrometerRange(mpu60xx_handle_t mpu_handle,mpu60xx_gyro_range_t * range ) +{ + uint8_t reg_value; + + esp_err_t ret = mpu60xx_read_register(mpu_handle,MPU60xx_GYRO_CFG_REG, ®_value, 1); + + if (ret == ESP_OK) { + *range = reg_value & 0x18; + } + return ret; +} + +esp_err_t mpu60xx_setSampleRate ( mpu60xx_handle_t mpu_handle, uint32_t sample_rate, mpu60xx_lowpass_t dlpf_bw) +{ + uint8_t cmd[2],smpl_rt_div=0; + uint32_t gy_out_rate = 8000; + esp_err_t ret; + + if (sample_rate<5) sample_rate =5; //minimum valid value =4.94 + + if (dlpf_bw!=MPU60XX_BAND_260_HZ) { + if (sample_rate>1000) sample_rate =1000; // max when DLPF used + gy_out_rate = 1000; + } + else if (sample_rate>8000) sample_rate =8000;// max when DLPF not used + + + ret = en_DLPF(mpu_handle, sample_rate); + if (ret !=ESP_OK) + return ret; + + smpl_rt_div = (uint8_t) ( gy_out_rate/ sample_rate) -1; + cmd[0] =MPU60xx_SMPRT_DIV; + cmd[1]= smpl_rt_div; + ret = mpu60xx_write_register(mpu_handle,MPU60xx_ADDR,cmd,2); + return ret; +} + +static esp_err_t en_DLPF( mpu60xx_handle_t mpu_handle, mpu60xx_lowpass_t b_width) +{ + uint8_t reg_value, cmd[2]; + esp_err_t ret; + + ret= mpu60xx_read_register(mpu_handle, MPU60xx_CFG_REG,®_value,1); + if (ret !=ESP_OK) { + ESP_LOGE(TAG,"unable to read MPU60xx_CFG_REG register"); + return ret; + } + + reg_value = reg_value & ((uint8_t)(~7)); + reg_value |= b_width; + + cmd[0] = MPU60xx_CFG_REG; + cmd[1] = reg_value; + ret= mpu60xx_write_register(mpu_handle,MPU60xx_ADDR,cmd, 2); + + if (ret !=ESP_OK) + ESP_LOGE(TAG,"unable to write to MPU60xx_CFG_REG register"); + return ret; + +} + +static esp_err_t en_DHPF( mpu60xx_handle_t mpu_handle, mpu60xx_highpass_t bandwidth) +{ + esp_err_t ret; + uint8_t reg_value,cmd[2]; + ret= mpu60xx_read_register(mpu_handle, MPU60xx_ACCEL_CFG_REG,®_value,1); + if (ret !=ESP_OK) { + ESP_LOGE(TAG,"unable to read MPU60xx_CFG_REG register"); + return ret; + } + + reg_value = reg_value & ((uint8_t)(~7)); + reg_value |= bandwidth; + + cmd[0] = MPU60xx_ACCEL_CFG_REG; + cmd[1] = reg_value; + ret= mpu60xx_write_register(mpu_handle,MPU60xx_ADDR,cmd, 2); + + if (ret !=ESP_OK) + ESP_LOGE(TAG,"unable to write to MPU60xx_CFG_REG register"); + + return ret; +} + + +esp_err_t mpu60xx_en_MotionDetection(mpu60xx_handle_t * mpu_handle,mpu60xx_motion_detect_config_t *mdc, mpu60xx_intrpt_config_t* interrupt_configuration) +{ + uint8_t cmd[2]; + esp_err_t ret; + + cmd[0] =MPU60xx_MOT_THR; + cmd[1]= mdc->motion_threshold; + ret = mpu60xx_write_register(*mpu_handle,MPU60xx_ADDR,cmd,2); + + + cmd[0] =MPU60xx_MOT_DUR; + cmd[1]= mdc->motion_duration; + ret = mpu60xx_write_register(*mpu_handle,MPU60xx_ADDR,cmd,2); + + en_DHPF(*mpu_handle,mdc->dhpf_bw); + mpu60xx_enMotionDetectInterrupt(mpu_handle, true); + + if (NULL != interrupt_configuration) { + if (GPIO_IS_VALID_GPIO(interrupt_configuration->interrupt_pin)) { + // Set GPIO connected to mpu60xx INT pin only when user configures interrupts. + // mpu60xx_dev_t *sensor_device = (mpu60xx_dev_t *) sensor; + // sensor_device->int_pin = interrupt_configuration->interrupt_pin; + } else { + ret = ESP_ERR_INVALID_ARG; + return ret; + } + + uint8_t int_pin_cfg = 0x00; + + ret = mpu60xx_read_register(*mpu_handle, MPU60xx_INT_PIN_CONFIG, &int_pin_cfg, 1); + + if (ESP_OK != ret) { + return ret; + } + + int_pin_cfg &= (uint8_t)~(BIT4 | BIT5 | BIT6 | BIT7); + + if (MPU60XX_INTERRUPT_PIN_ACTIVE_LOW == interrupt_configuration->active_level) { + int_pin_cfg |= BIT7; + } + + if (MPU60XX_INTERRUPT_PIN_OPEN_DRAIN == interrupt_configuration->pin_mode) { + int_pin_cfg |= BIT6; + } + + if (MPU60XX_INTERRUPT_LATCH_UNTIL_CLEARED == interrupt_configuration->interrupt_latch) { + int_pin_cfg |= BIT5; + } + + if (MPU60XX_INTERRUPT_CLEAR_ON_ANY_READ == interrupt_configuration->interrupt_clear_behavior) { + int_pin_cfg |= BIT4; + } + + cmd[0] = MPU60xx_INT_PIN_CONFIG; + cmd[1] = int_pin_cfg; + ret = mpu60xx_write_register(*mpu_handle, MPU60xx_ADDR, cmd, 2); + + gpio_int_type_t gpio_intr_type; + uint8_t pull_up=0, pull_down=0; + + if (MPU60XX_INTERRUPT_PIN_ACTIVE_LOW == interrupt_configuration->active_level) { + gpio_intr_type = GPIO_INTR_NEGEDGE; + pull_up=1; + } else { + gpio_intr_type = GPIO_INTR_POSEDGE; + pull_down=1; + } + + gpio_config_t int_gpio_config = { + .mode = GPIO_MODE_INPUT, + .intr_type = gpio_intr_type, + .pin_bit_mask = (BIT0 << interrupt_configuration->interrupt_pin), + .pull_up_en = pull_up, + .pull_down_en=pull_down, + }; + + ret = gpio_config(&int_gpio_config); + + ret= register_isr(mpu_handle,interrupt_configuration); + } + + return ret; +} + + +esp_err_t mpu60xx_enMotionDetectInterrupt(mpu60xx_handle_t * mpu_handle, bool active) +{ + uint8_t reg_value, cmd[2]; + + esp_err_t ret= mpu60xx_read_register(*mpu_handle, MPU60xx_INT_EN_REG,®_value,1); + if (ret !=ESP_OK) { + ESP_LOGE(TAG,"unable to read MPU60xx_INT_EN_REG register"); + return ret; + } + if (active) + reg_value |= (BIT6); + else + reg_value = reg_value & ((uint8_t)(~BIT6)); + + cmd[0] = MPU60xx_INT_EN_REG; + cmd[1] = reg_value; + ret= mpu60xx_write_register(*mpu_handle,MPU60xx_ADDR,cmd, 2); + + if (ret !=ESP_OK) + ESP_LOGE(TAG,"unable to write to MPU60xx_INT_EN_REG register"); + +return ret; +} + +static esp_err_t register_isr(mpu60xx_handle_t * sensor, mpu60xx_intrpt_config_t* interrupt_configuration) +{ + esp_err_t ret; + + gpio_install_isr_service(0); + ret = gpio_isr_handler_add( + interrupt_configuration->interrupt_pin, + ((gpio_isr_t) * (interrupt_configuration->isr)), + NULL + ); + + if ( ret != ESP_OK ) { + return ret; + } + return ret; +} + +esp_err_t mpu60xx_getMotionInterruptStatus(mpu60xx_handle_t mpu_handle, bool * status) +{ + uint8_t reg_value; + esp_err_t ret; + ret= mpu60xx_read_register(mpu_handle, MPU60xx_INT_STATUS,®_value,1); + if (ret == ESP_OK) { + reg_value = reg_value & ((uint8_t)(64)); + if (reg_value) + *status = true; + else + *status = false; + } + else + ESP_LOGE(TAG,"unable to read MPU60xx_INT_EN_REG register"); + return ret; + +} + +esp_err_t mpu60xx_read_sensor_raw (mpu60xx_handle_t mpu_handle, mpu60xx_reading_raw_t * sensor_raw_read) +{ + uint8_t data[14]; + esp_err_t ret = mpu60xx_read_register(mpu_handle,MPU60xx_ACCEL_XOUTH_REG, data, 14); + if ( ret == ESP_OK) { + sensor_raw_read->accX_raw = ((uint16_t)data[0] << 8) | data[1]; + sensor_raw_read->accY_raw = ((uint16_t)data[2] << 8) | data[3]; + sensor_raw_read->accZ_raw = ((uint16_t)data[4] << 8) | data[5]; + + sensor_raw_read->temp_raw = ((uint16_t)data[6] << 8) | data[7]; + + + sensor_raw_read->gyroX_raw = ((uint16_t)data[8] << 8) | data[9]; + sensor_raw_read->gyroY_raw = ((uint16_t)data[10] << 8) | data[11]; + sensor_raw_read->gyroZ_raw = ((uint16_t)data[12] << 8) | data[13]; + } + else + ESP_LOGE(TAG, "Failed to read from MPU60xx"); + + return ret; +} + + +esp_err_t mpu60xx_read_sensor(mpu60xx_handle_t mpu_handle, mpu60xx_reading_t * sensor_t) +{ + mpu60xx_reading_raw_t sensor_raw_read; + esp_err_t ret = mpu60xx_read_sensor_raw(mpu_handle,&sensor_raw_read); + + if ( ret == ESP_OK) { + sensor_t->temperature = 36.53 + ( (int16_t)sensor_raw_read.temp_raw )/340.0; + + mpu60xx_accel_range_t accel_range; + ret= getAccelerometerRange(mpu_handle, &accel_range); + if (ret==ESP_OK) { + float accel_scale = 1; + // select appropriate scale based on range + switch (accel_range) { + case MPU60XX_RANGE_2_G: accel_scale = 16384; + break; + + case MPU60XX_RANGE_4_G: accel_scale = 8192; + break; + + case MPU60XX_RANGE_8_G: accel_scale = 4096; + break; + + case MPU60XX_RANGE_16_G: accel_scale = 2048; + break; + } + + // raw values provide results in terms of 'g'(standard acceleration of gravity), + // multiply with 's_g_value' to convert into 'm/s^2' + sensor_t->accX = s_g_value*((float_t) sensor_raw_read.accX_raw) / accel_scale; + sensor_t->accY = s_g_value*((float_t) sensor_raw_read.accY_raw) / accel_scale; + sensor_t->accZ = s_g_value*((float_t) sensor_raw_read.accZ_raw) / accel_scale; + } + else { + ESP_LOGE(TAG, "Failed to get Accelerometer Range from MPU60xx"); + return ret; + } + + + mpu60xx_gyro_range_t gyro_range; + ret= getGyrometerRange(mpu_handle, &gyro_range); + if (ret==ESP_OK) { + float gyro_scale = 1; + + // select appropriate scale based on range + switch (gyro_range) { + case MPU60XX_RANGE_250_DEG: gyro_scale = 131; + break; + + case MPU60XX_RANGE_500_DEG: gyro_scale = 65.5; + break; + + case MPU60XX_RANGE_1000_DEG: gyro_scale = 32.8; + break; + + case MPU60XX_RANGE_2000_DEG: gyro_scale = 16.4; + break; + } + + // setup range dependant scaling + sensor_t->gyroX = ((float_t) sensor_raw_read.gyroX_raw) / gyro_scale; + sensor_t->gyroY = ((float_t) sensor_raw_read.gyroY_raw) / gyro_scale; + sensor_t->gyroZ = ((float_t) sensor_raw_read.gyroZ_raw) / gyro_scale; + } + else { + ESP_LOGE(TAG, "Failed to get Gyrometer Range from MPU60xx"); + return ret; + } + } + else + ESP_LOGE(TAG, "Failed to read from MPU60xx"); + + return ret; +} + + +esp_err_t mpu60xx_init(mpu60xx_init_config_t config_handle, mpu60xx_handle_t mpu_handle) +{ + esp_err_t ret ; + + ret= i2c_master_probe(*mpu_handle.bus_handle, MPU60xx_ADDR, 50); + + if (ret!=ESP_OK) { + ESP_LOGE(TAG, "mpu60xx not detected on i2c"); + return ret; + } + + ESP_LOGI(TAG, "mpu60xx is available\n"); + + i2c_device_config_t mpu_60xx_config = { + .dev_addr_length = I2C_ADDR_BIT_LEN_7, + .device_address = MPU60xx_ADDR, + .scl_speed_hz = config_handle.scl_speed_hz, + }; + + ESP_LOGI(TAG, "adding mpu60xx as device to bus\n"); + + ESP_ERROR_CHECK(i2c_master_bus_add_device(*mpu_handle.bus_handle, &mpu_60xx_config, mpu_handle.dev_handle)); + + ESP_LOGI(TAG, "device added to bus\n"); + + uint8_t cmd[2]; + + //reset MPU60xx + cmd[0] =MPU60xx_PWR_MGMT1_REG; + cmd[1]= 0x80; + ESP_ERROR_CHECK(mpu60xx_write_register(mpu_handle, MPU60xx_ADDR,cmd,2)); + vTaskDelay(100/portTICK_PERIOD_MS); + + if(config_handle.temp_sensor == true){ //enable temperature sensor, default is disabled + cmd[0] =MPU60xx_PWR_MGMT1_REG; + cmd[1]= 0x00; + ESP_ERROR_CHECK(mpu60xx_write_register(mpu_handle,MPU60xx_ADDR,cmd,2)); + } + + + mpu60xx_setGyrometerRange(mpu_handle, config_handle.gyro_res); + + mpu60xx_setAccelerometerRange(mpu_handle, config_handle.accel_res); + + mpu60xx_setSampleRate(mpu_handle, config_handle.sample_rate, config_handle.dlpf_bw); + + cmd[0] =MPU60xx_INT_EN_REG; + cmd[1]= 0x00; + mpu60xx_write_register(mpu_handle,MPU60xx_ADDR,cmd,2); + + cmd[0] =MPU60xx_USER_CTRL_REG; + cmd[1]= 0x00; + mpu60xx_write_register(mpu_handle,MPU60xx_ADDR,cmd,2); + + ESP_LOGI(TAG, "mpu60xx initialization complete\n"); + return ESP_OK; +} From 94bba2663ccbd902c1718aedc430d2065674fece Mon Sep 17 00:00:00 2001 From: jeetrohan Date: Tue, 22 Oct 2024 22:45:18 +0530 Subject: [PATCH 4/9] Create idf_component.yml manifest file for mpu60xx driver --- components/mpu60xx/idf_component.yml | 27 +++++++++++++++++++++++++++ 1 file changed, 27 insertions(+) create mode 100644 components/mpu60xx/idf_component.yml diff --git a/components/mpu60xx/idf_component.yml b/components/mpu60xx/idf_component.yml new file mode 100644 index 00000000..bb5fdf0a --- /dev/null +++ b/components/mpu60xx/idf_component.yml @@ -0,0 +1,27 @@ +## IDF Component Manager Manifest File + +description: MPU60xx I2C driver + +maintainers: + - "Rohan Jeet " + +dependencies: + ## Required IDF version + idf: + version: ">=4.1.0" + # # Put list of dependencies here + # + # # For components maintained by Espressif: + # component: "~1.0.0" + # + esp_driver_i2c: "*" + esp_driver_gpio: "*" + # + # # For 3rd party components: + # username/component: ">=1.0.0,<2.0.0" + # username2/component2: + # version: "~1.0.0" + # # For transient dependencies `public` flag can be set. + # # `public` flag doesn't have an effect dependencies of the `main` component. + # # All dependencies of `main` are public by default. + # public: true From dca48ccb319ad71a34b6d7eda560dcb94d099d87 Mon Sep 17 00:00:00 2001 From: jeetrohan Date: Tue, 22 Oct 2024 23:06:50 +0530 Subject: [PATCH 5/9] mpu_motion_detect.c example C source file for using inbuilt motion detection. --- .../main/mpu_motion_detect.c | 122 ++++++++++++++++++ 1 file changed, 122 insertions(+) create mode 100644 components/mpu60xx/examples/mpu_motion_detect/main/mpu_motion_detect.c diff --git a/components/mpu60xx/examples/mpu_motion_detect/main/mpu_motion_detect.c b/components/mpu60xx/examples/mpu_motion_detect/main/mpu_motion_detect.c new file mode 100644 index 00000000..5a4dc1cb --- /dev/null +++ b/components/mpu60xx/examples/mpu_motion_detect/main/mpu_motion_detect.c @@ -0,0 +1,122 @@ +/* + * mpu60xx.h + * + * Created on: 15-Oct-2024 + * Author: rohan + */ + +#include "freertos/FreeRTOS.h" +#include "mpu60xx.h" + + + +//i2c configuration values +#define I2C_MASTER_SCL_IO (22) // SCL pin +#define I2C_MASTER_SDA_IO (21) // SDA pin +#define I2C_MASTER_NUM I2C_NUM_0 +#define I2C_MASTER_FREQ_HZ (100000) // I2C frequency + +#define MPU_INTERRUPT_PIN (23) + + + +i2c_master_bus_handle_t my_bus_handle; +i2c_master_dev_handle_t my_mpu_60xx_handle; + +TaskHandle_t handler_task; +static SemaphoreHandle_t s_bin_sem; + +#define ESP_INTR_FLAG_DEFAULT 0 + + + + void i2c_master_init(void) { + i2c_master_bus_config_t i2c_mst_config = { + .clk_source = I2C_CLK_SRC_DEFAULT, + .i2c_port = I2C_MASTER_NUM , + .scl_io_num = I2C_MASTER_SCL_IO, + .sda_io_num = I2C_MASTER_SDA_IO, + .glitch_ignore_cnt = 7, + .flags.enable_internal_pullup = true, +}; + printf("requesting i2c bus handle\n"); +ESP_ERROR_CHECK(i2c_new_master_bus(&i2c_mst_config, &my_bus_handle)); + printf("i2c bus handle acquired\n"); + + +} + + volatile uint32_t count =0; + void intr_isr_handler(void * arg) +{ + //vTaskResume(handler_task); + BaseType_t xHigherPriorityTaskWoken = pdFALSE; + xSemaphoreGiveFromISR(s_bin_sem, &xHigherPriorityTaskWoken); +} + +void read_data(void * mpu_handle){ + + mpu60xx_reading_t sensor_data; + mpu60xx_handle_t my_dev_handle = *(mpu60xx_handle_t*)mpu_handle; + bool status; + while (1) { + + if(xSemaphoreTake(s_bin_sem, 20/portTICK_PERIOD_MS) == pdPASS){ + ESP_ERROR_CHECK( mpu60xx_read_sensor (my_dev_handle , &sensor_data )); + printf("aX = %.3f m/s, aY = %.3f m/s, aZ = %.3f m/s, t=%.3f C, gX = %.3f dps gY = %.3f dps gZ = %.3f dps\n", sensor_data.accX, sensor_data.accY, sensor_data.accZ, sensor_data.temperature,sensor_data.gyroX, sensor_data.gyroY, sensor_data.gyroZ); + ESP_ERROR_CHECK(mpu60xx_getMotionInterruptStatus(my_dev_handle,&status)); + } + } +} + + +void app_main(void) { + + //static const mpu60xx_reading sensor_data; + i2c_master_init(); + + mpu60xx_init_config_t mpu_6050_config = + { + .scl_speed_hz = I2C_MASTER_FREQ_HZ, + .gyro_res= MPU60XX_RANGE_500_DEG, + .accel_res = MPU60XX_RANGE_8_G, + .temp_sensor=true, + .dlpf_bw =MPU60XX_BAND_94_HZ, + .sample_rate= 200 + }; + + mpu60xx_handle_t dev_6050_handle = { + .bus_handle = &my_bus_handle, + .dev_handle = &my_mpu_60xx_handle + }; + + printf("requesting mpu handle\n"); + while (mpu60xx_init(mpu_6050_config, dev_6050_handle) != ESP_OK) + vTaskDelay(200/portTICK_PERIOD_MS); + printf("mpu handle acquired\n"); + + + + mpu60xx_motion_detect_config_t mot_det= + { + .motion_threshold=2, + .motion_duration=10, + .dhpf_bw=MPU60XX_HIGHPASS_0_63_HZ + }; + + mpu60xx_intrpt_config_t md_intr_conf = { + .interrupt_pin =(gpio_num_t)MPU_INTERRUPT_PIN, + .active_level = MPU60XX_INTERRUPT_PIN_ACTIVE_LOW, + .pin_mode = MPU60XX_INTERRUPT_PIN_PUSH_PULL, + .interrupt_latch = MPU60XX_INTERRUPT_LATCH_UNTIL_CLEARED, + .interrupt_clear_behavior = MPU60XX_INTERRUPT_CLEAR_ON_STATUS_READ, + .isr = intr_isr_handler + }; + + vTaskDelay(200/portTICK_PERIOD_MS); + mpu60xx_en_MotionDetection(&dev_6050_handle,&mot_det,&md_intr_conf); + s_bin_sem=xSemaphoreCreateBinary(); + + xTaskCreate(read_data, "apna_imu_tester", 2500, &dev_6050_handle, 5, &handler_task); +} + From 9562071ec0a2fa9b10c6f92db2e6b3b25ccd4241 Mon Sep 17 00:00:00 2001 From: jeetrohan Date: Tue, 22 Oct 2024 23:11:52 +0530 Subject: [PATCH 6/9] idf_component.yml Manifest file for mpu60xx_motion_detection example --- .../mpu_motion_detect/main/idf_component.yml | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) create mode 100644 components/mpu60xx/examples/mpu_motion_detect/main/idf_component.yml diff --git a/components/mpu60xx/examples/mpu_motion_detect/main/idf_component.yml b/components/mpu60xx/examples/mpu_motion_detect/main/idf_component.yml new file mode 100644 index 00000000..5b2e19c7 --- /dev/null +++ b/components/mpu60xx/examples/mpu_motion_detect/main/idf_component.yml @@ -0,0 +1,18 @@ +## IDF Component Manager Manifest File +dependencies: + ## Required IDF version + idf: + version: ">=4.1.0" + # # Put list of dependencies here + mpu60xx: + version: "*" + # # For components maintained by Espressif: + # component: "~1.0.0" + # # For 3rd party components: + # username/component: ">=1.0.0,<2.0.0" + # username2/component2: + # version: "~1.0.0" + # # For transient dependencies `public` flag can be set. + # # `public` flag doesn't have an effect dependencies of the `main` component. + # # All dependencies of `main` are public by default. + # public: true From 6d8b0c6bb7b70501fb628d2d032a979949e467e3 Mon Sep 17 00:00:00 2001 From: jeetrohan Date: Tue, 22 Oct 2024 23:13:48 +0530 Subject: [PATCH 7/9] CMakeLists.txt CMakeLists for mpu60xx_motion_detect --- .../mpu60xx/examples/mpu_motion_detect/main/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) create mode 100644 components/mpu60xx/examples/mpu_motion_detect/main/CMakeLists.txt diff --git a/components/mpu60xx/examples/mpu_motion_detect/main/CMakeLists.txt b/components/mpu60xx/examples/mpu_motion_detect/main/CMakeLists.txt new file mode 100644 index 00000000..0879c5b1 --- /dev/null +++ b/components/mpu60xx/examples/mpu_motion_detect/main/CMakeLists.txt @@ -0,0 +1,2 @@ +idf_component_register(SRCS "mpu60xx_motion_detect.c" + INCLUDE_DIRS ".") From 5b8d56011fd50ffce286916d30e3967bcd75c38d Mon Sep 17 00:00:00 2001 From: jeetrohan Date: Tue, 22 Oct 2024 23:15:07 +0530 Subject: [PATCH 8/9] CmakeLists.txt --- .../mpu60xx/examples/mpu_motion_detect/CmakeLists.txt | 9 +++++++++ 1 file changed, 9 insertions(+) create mode 100644 components/mpu60xx/examples/mpu_motion_detect/CmakeLists.txt diff --git a/components/mpu60xx/examples/mpu_motion_detect/CmakeLists.txt b/components/mpu60xx/examples/mpu_motion_detect/CmakeLists.txt new file mode 100644 index 00000000..144aa92b --- /dev/null +++ b/components/mpu60xx/examples/mpu_motion_detect/CmakeLists.txt @@ -0,0 +1,9 @@ +# For more information about build system see +# https://docs.espressif.com/projects/esp-idf/en/latest/api-guides/build-system.html +# The following five lines of boilerplate have to be in your project's +# CMakeLists in this exact order for cmake to work correctly +cmake_minimum_required(VERSION 3.16) + +set(COMPONENTS main) +include($ENV{IDF_PATH}/tools/cmake/project.cmake) +project(mpu60xx_motion_detect) From 13d9955844fd86c36fa76bc59aa2e6119bf97674 Mon Sep 17 00:00:00 2001 From: jeetrohan Date: Tue, 22 Oct 2024 23:16:52 +0530 Subject: [PATCH 9/9] README.md mpu60xx driver information. --- components/mpu60xx/README.md | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) create mode 100644 components/mpu60xx/README.md diff --git a/components/mpu60xx/README.md b/components/mpu60xx/README.md new file mode 100644 index 00000000..3eac5bf0 --- /dev/null +++ b/components/mpu60xx/README.md @@ -0,0 +1,22 @@ +# mpu60xx +I2C driver for MPU60xx family IMU. + +## Features + - Read Accelerometer, Gyrometer and Temperature sensor as raw or floating values. + - Use in-buit Motion Detection feature using either interrupt or polling. + +## Limitations + - Does NOT support esp-idf Legacy I2C driver (documentation indicates it'll be removed in future releases). + - Not tested with MPU6000. ( TRM indicates it should also work, same register set as MPU6050.) + - Supports only I2C protocol ( Only MPU6000 has SPI capability.) + +## Important Note + - Use deferred processing to handle interrupts from MPU60xx, I2C driver require interrupt to read/write (see example). + - INT pin of MPU60xx is required to be connected to esp32 gpio for interrupt. + +## Feature for next release (planned) + MPU60xx has many more features which haven't been implemented in this library currently, but are planned to be added in further releases. The next intended feature is + - Zero motion detection. + + +