diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index ebded7123..dee73cfd2 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -81,6 +81,8 @@ jobs: target: esp32s3 - path: 'components/i2c/example' target: esp32 + - path: 'components/icm42607/example' + target: esp32s3 - path: 'components/interrupt/example' target: esp32s3 - path: 'components/joystick/example' diff --git a/components/base_peripheral/include/base_peripheral.hpp b/components/base_peripheral/include/base_peripheral.hpp index 29aabb9f7..5f7ca0640 100644 --- a/components/base_peripheral/include/base_peripheral.hpp +++ b/components/base_peripheral/include/base_peripheral.hpp @@ -636,6 +636,28 @@ class BasePeripheral : public BaseComponent { write_u8_to_register(register_address, data, ec); } + /// Set bits in a register on the peripheral by mask + /// \param register_address The address of the register to modify + /// \param mask The mask to use when setting the bits. All bits not in the + /// mask will be unmodified, while all bits within the mask will + /// be set to the value of the corresponding bit in the value + /// \param value The value to set. Bits in the value should correspond to the + /// bits in the mask + /// \param ec The error code to set if there is an error + void set_bits_in_register_by_mask(RegisterAddressType register_address, uint8_t mask, + uint8_t value, std::error_code &ec) { + logger_.debug("set_bits_in_register_by_mask 0x{:x} with mask 0x{:x} and value 0x{:x}", + register_address, mask, value); + std::lock_guard lock(base_mutex_); + uint8_t data = read_u8_from_register(register_address, ec); + if (ec) { + return; + } + data &= ~mask; + data |= value & mask; + write_u8_to_register(register_address, data, ec); + } + /// Clear bits in a register on the peripheral /// \param register_address The address of the register to modify /// \param mask The mask to clear diff --git a/components/bldc_motor/include/bldc_motor.hpp b/components/bldc_motor/include/bldc_motor.hpp index 289388920..8af645434 100644 --- a/components/bldc_motor/include/bldc_motor.hpp +++ b/components/bldc_motor/include/bldc_motor.hpp @@ -407,8 +407,9 @@ class BldcMotor : public BaseComponent { float Uout; // a bit of optitmisation if (ud) { // only if ud and uq set - // fast_sqrt is an approx of sqrt (3-4% error) - Uout = fast_sqrt(ud * ud + uq * uq) / driver_->get_voltage_limit(); + // fast_inv_sqrt is an approx of invsqrt (3-4% error), so we need to + // invert it to get the correct value (1/inv_sqrt = sqrt) + Uout = 1.0f / (fast_inv_sqrt(ud * ud + uq * uq) * driver_->get_voltage_limit()); // angle normalisation in between 0 and 2pi // only necessary if using fast_sin and fast_cos - approximation functions el_angle = normalize_angle(el_angle + atan2(uq, ud)); diff --git a/components/esp-box/CMakeLists.txt b/components/esp-box/CMakeLists.txt index c6d777765..110166c8f 100644 --- a/components/esp-box/CMakeLists.txt +++ b/components/esp-box/CMakeLists.txt @@ -1,6 +1,6 @@ idf_component_register( INCLUDE_DIRS "include" SRC_DIRS "src" - REQUIRES driver base_component codec display display_drivers i2c input_drivers interrupt gt911 task tt21100 + REQUIRES driver base_component codec display display_drivers i2c input_drivers interrupt gt911 task tt21100 icm42607 REQUIRED_IDF_TARGETS "esp32s3" ) diff --git a/components/esp-box/example/CMakeLists.txt b/components/esp-box/example/CMakeLists.txt index e1a15d579..529bec6c9 100644 --- a/components/esp-box/example/CMakeLists.txt +++ b/components/esp-box/example/CMakeLists.txt @@ -11,7 +11,7 @@ set(EXTRA_COMPONENT_DIRS set( COMPONENTS - "main esptool_py esp-box" + "main esptool_py esp-box filters" CACHE STRING "List of components to include" ) diff --git a/components/esp-box/example/README.md b/components/esp-box/example/README.md index 4e3871669..dba524ce9 100644 --- a/components/esp-box/example/README.md +++ b/components/esp-box/example/README.md @@ -9,10 +9,13 @@ state and each time you touch the scren it 1) uses LVGL to draw a circle where you touch, and 2) play a click sound (wav file bundled with the firmware). If you press the home button on the display, it will clear the circles. +https://github.com/user-attachments/assets/6fc9ce02-fdae-4f36-9ee7-3a6c347ca1c4 + https://github.com/esp-cpp/espp/assets/213467/d5379983-9bc2-4d56-a9fc-9e37f54af15e ![image](https://github.com/esp-cpp/espp/assets/213467/bfb45218-0d1f-4a07-ba30-c0c74a1657b9) ![image](https://github.com/esp-cpp/espp/assets/213467/c7216cfd-330d-4610-baf2-30001c98ff42) +![image](https://github.com/user-attachments/assets/6d9901f1-f4fe-433a-b6d5-c8c82abd14b7) ## How to use example @@ -42,3 +45,16 @@ BOX3: BOX: ![CleanShot 2024-07-01 at 09 56 23](https://github.com/esp-cpp/espp/assets/213467/2f758ff5-a82e-4620-896e-99223010f013) + +Slow rotation video: + +https://github.com/user-attachments/assets/6fc9ce02-fdae-4f36-9ee7-3a6c347ca1c4 + +Fast rotation video: + +https://github.com/user-attachments/assets/64fd1d71-d6b2-4c4f-8538-4097d4d162e9 + +Pictures showing the new gravity vector pointing down from the center of the screen: +![image](https://github.com/user-attachments/assets/0a971b19-95b9-468c-8d5b-e99f2fbf76b9) +![image](https://github.com/user-attachments/assets/6d9901f1-f4fe-433a-b6d5-c8c82abd14b7) + diff --git a/components/esp-box/example/main/esp_box_example.cpp b/components/esp-box/example/main/esp_box_example.cpp index 8968ed423..fe2015764 100644 --- a/components/esp-box/example/main/esp_box_example.cpp +++ b/components/esp-box/example/main/esp_box_example.cpp @@ -5,6 +5,9 @@ #include "esp-box.hpp" +#include "kalman_filter.hpp" +#include "madgwick_filter.hpp" + using namespace std::chrono_literals; static constexpr size_t MAX_CIRCLES = 100; @@ -80,6 +83,12 @@ extern "C" void app_main(void) { return; } + // initialize the IMU + if (!box.initialize_imu()) { + logger.error("Failed to initialize IMU!"); + return; + } + // set the background color to black lv_obj_t *bg = lv_obj_create(lv_screen_active()); lv_obj_set_size(bg, box.lcd_width(), box.lcd_height()); @@ -87,9 +96,37 @@ extern "C" void app_main(void) { // add text in the center of the screen lv_obj_t *label = lv_label_create(lv_screen_active()); - lv_label_set_text(label, "Touch the screen!\nPress the home button to clear circles."); - lv_obj_align(label, LV_ALIGN_CENTER, 0, 0); - lv_obj_set_style_text_align(label, LV_TEXT_ALIGN_CENTER, 0); + static std::string label_text = + "\n\n\n\nTouch the screen!\nPress the home button to clear circles."; + lv_label_set_text(label, label_text.c_str()); + lv_obj_align(label, LV_ALIGN_TOP_LEFT, 0, 0); + lv_obj_set_style_text_align(label, LV_TEXT_ALIGN_LEFT, 0); + + /*Create style*/ + static lv_style_t style_line0; + lv_style_init(&style_line0); + lv_style_set_line_width(&style_line0, 8); + lv_style_set_line_color(&style_line0, lv_palette_main(LV_PALETTE_BLUE)); + lv_style_set_line_rounded(&style_line0, true); + + // make a line for showing the direction of "down" + lv_obj_t *line0 = lv_line_create(lv_screen_active()); + static lv_point_precise_t line_points0[] = {{0, 0}, {box.lcd_width(), box.lcd_height()}}; + lv_line_set_points(line0, line_points0, 2); + lv_obj_add_style(line0, &style_line0, 0); + + /*Create style*/ + static lv_style_t style_line1; + lv_style_init(&style_line1); + lv_style_set_line_width(&style_line1, 8); + lv_style_set_line_color(&style_line1, lv_palette_main(LV_PALETTE_RED)); + lv_style_set_line_rounded(&style_line1, true); + + // make a line for showing the direction of "down" + lv_obj_t *line1 = lv_line_create(lv_screen_active()); + static lv_point_precise_t line_points1[] = {{0, 0}, {box.lcd_width(), box.lcd_height()}}; + lv_line_set_points(line1, line_points1, 2); + lv_obj_add_style(line1, &style_line1, 0); // add a button in the top left which (when pressed) will rotate the display // through 0, 90, 180, 270 degrees @@ -129,6 +166,7 @@ extern "C" void app_main(void) { }, .task_config = { .name = "lv_task", + .stack_size_bytes = 6 * 1024, }}); lv_task.start(); @@ -143,6 +181,112 @@ extern "C" void app_main(void) { // set the display brightness to be 75% box.brightness(75.0f); + // make a task to read out the IMU data and print it to console + espp::Task imu_task( + {.callback = [&label, &line0, &line1](std::mutex &m, std::condition_variable &cv) -> bool { + // sleep first in case we don't get IMU data and need to exit early + { + std::unique_lock lock(m); + cv.wait_for(lock, 10ms); + } + static auto &box = espp::EspBox::get(); + static auto imu = box.imu(); + + auto now = esp_timer_get_time(); // time in microseconds + static auto t0 = now; + auto t1 = now; + float dt = (t1 - t0) / 1'000'000.0f; // convert us to s + t0 = t1; + + std::error_code ec; + // get accel + auto accel = imu->get_accelerometer(ec); + if (ec) { + return false; + } + auto gyro = imu->get_gyroscope(ec); + if (ec) { + return false; + } + auto temp = imu->get_temperature(ec); + if (ec) { + return false; + } + + // with only the accelerometer + gyroscope, we can't get yaw :( + float roll = 0, pitch = 0; + static constexpr float angle_noise = 0.001f; + static constexpr float rate_noise = 0.1f; + static espp::KalmanFilter<2> kf; + kf.set_process_noise(rate_noise); + kf.set_measurement_noise(angle_noise); + static constexpr float beta = 0.1f; // higher = more accelerometer, lower = more gyro + static espp::MadgwickFilter f(beta); + + f.update(dt, accel.x, accel.y, accel.z, gyro.x * M_PI / 180.0f, gyro.y * M_PI / 180.0f, + gyro.z * M_PI / 180.0f); + float yaw; // ignore / unused since we only have 6-axis + f.get_euler(roll, pitch, yaw); + pitch *= M_PI / 180.0f; + roll *= M_PI / 180.0f; + + std::string text = fmt::format("{}\n\n\n\n\n", label_text); + text += fmt::format("Accel: {:02.2f} {:02.2f} {:02.2f}\n", accel.x, accel.y, accel.z); + text += fmt::format("Gyro: {:03.2f} {:03.2f} {:03.2f}\n", gyro.x * M_PI / 180.0f, + gyro.y * M_PI / 180.0f, gyro.z * M_PI / 180.0f); + text += + fmt::format("Angle: {:03.2f} {:03.2f}\n", roll * 180.0f / M_PI, pitch * 180.0f / M_PI); + text += fmt::format("Temp: {:02.1f} C\n", temp); + + // use the pitch to to draw a line on the screen indiating the + // direction from the center of the screen to "down" + int x0 = box.lcd_width() / 2; + int y0 = box.lcd_height() / 2; + + float vx = sin(pitch); + float vy = -cos(pitch) * sin(roll); + float vz = -cos(pitch) * cos(roll); + + int x1 = x0 + 50 * vx; + int y1 = y0 + 50 * vy; + + static lv_point_precise_t line_points0[] = {{x0, y0}, {x1, y1}}; + line_points0[1].x = x1; + line_points0[1].y = y1; + + // Apply Kalman filter + float accelPitch = atan2(-accel.x, sqrt(accel.y * accel.y + accel.z * accel.z)); + float accelRoll = atan2(accel.y, accel.z); + kf.predict({float(gyro.x * M_PI / 180.0f), float(gyro.y * M_PI / 180.0f)}, dt); + kf.update({accelPitch, accelRoll}); + std::tie(pitch, roll) = kf.get_state(); + + vx = sin(pitch); + vy = -cos(pitch) * sin(roll); + vz = -cos(pitch) * cos(roll); + + x1 = x0 + 50 * vx; + y1 = y0 + 50 * vy; + + static lv_point_precise_t line_points1[] = {{x0, y0}, {x1, y1}}; + line_points1[1].x = x1; + line_points1[1].y = y1; + + std::lock_guard lock(lvgl_mutex); + lv_label_set_text(label, text.c_str()); + lv_line_set_points(line0, line_points0, 2); + lv_line_set_points(line1, line_points1, 2); + + return false; + }, + .task_config = { + .name = "IMU", + .stack_size_bytes = 6 * 1024, + .priority = 10, + .core_id = 0, + }}); + imu_task.start(); + // loop forever while (true) { std::this_thread::sleep_for(1s); diff --git a/components/esp-box/include/esp-box.hpp b/components/esp-box/include/esp-box.hpp index 5b7f4ec8e..7472855a2 100644 --- a/components/esp-box/include/esp-box.hpp +++ b/components/esp-box/include/esp-box.hpp @@ -19,6 +19,7 @@ #include "es8311.hpp" #include "gt911.hpp" #include "i2c.hpp" +#include "icm42607.hpp" #include "interrupt.hpp" #include "st7789.hpp" #include "touchpad_input.hpp" @@ -32,6 +33,9 @@ namespace espp { /// - Touchpad /// - Display /// - Audio +/// - Interrupts +/// - I2C +/// - IMU (Inertial Measurement Unit) /// /// The class is a singleton and can be accessed using the get() method. /// @@ -44,8 +48,13 @@ class EspBox : public BaseComponent { /// Alias for the display driver used by the ESP-Box display using DisplayDriver = espp::St7789; + + /// Alias for the touchpad data used by the ESP-Box touchpad using TouchpadData = espp::TouchpadData; + /// Alias the IMU used by the ESP-Box + using Imu = espp::Icm42607; + /// The type of the box enum class BoxType { UNKNOWN, ///< unknown box @@ -286,6 +295,18 @@ class EspBox : public BaseComponent { /// \param num_bytes The number of bytes to play void play_audio(const uint8_t *data, uint32_t num_bytes); + ///////////////////////////////////////////////////////////////////////////// + // IMU + ///////////////////////////////////////////////////////////////////////////// + + /// Initialize the IMU + /// \return true if the IMU was successfully initialized, false otherwise + bool initialize_imu(); + + /// Get the IMU + /// \return A shared pointer to the IMU + std::shared_ptr imu() const; + protected: EspBox(); void detect(); @@ -440,6 +461,9 @@ class EspBox : public BaseComponent { i2s_std_config_t audio_std_cfg; i2s_event_callbacks_t audio_tx_callbacks_; std::atomic has_sound{false}; + + // IMU + std::shared_ptr imu_; }; // class EspBox } // namespace espp diff --git a/components/esp-box/src/imu.cpp b/components/esp-box/src/imu.cpp new file mode 100644 index 000000000..e8644433e --- /dev/null +++ b/components/esp-box/src/imu.cpp @@ -0,0 +1,59 @@ +#include "esp-box.hpp" + +using namespace espp; + +bool EspBox::initialize_imu() { + if (imu_) { + logger_.warn("IMU already initialized, not initializing again!"); + return false; + } + + Imu::Config config{ + .device_address = Imu::DEFAULT_ADDRESS, + .write = std::bind(&espp::I2c::write, &internal_i2c_, std::placeholders::_1, + std::placeholders::_2, std::placeholders::_3), + .read = std::bind(&espp::I2c::read, &internal_i2c_, std::placeholders::_1, + std::placeholders::_2, std::placeholders::_3), + .imu_config = + { + .accelerometer_range = Imu::AccelerometerRange::RANGE_2G, + .accelerometer_odr = Imu::AccelerometerODR::ODR_400_HZ, + .gyroscope_range = Imu::GyroscopeRange::RANGE_2000DPS, + .gyroscope_odr = Imu::GyroscopeODR::ODR_400_HZ, + }, + .auto_init = true, + }; + + logger_.info("Initializing IMU with default configuration"); + imu_ = std::make_shared(config); + + // configure the dmp + std::error_code ec; + // turn on DMP + if (!imu_->set_dmp_power_save(false, ec)) { + logger_.error("Failed to set DMP power save mode: {}", ec.message()); + return false; + } + if (!imu_->dmp_initialize(ec)) { + logger_.error("Failed to initialize DMP: {}", ec.message()); + return false; + } + if (!imu_->set_dmp_odr(icm42607::DmpODR::ODR_25_HZ, ec)) { + logger_.error("Failed to set DMP ODR: {}", ec.message()); + return false; + } + // set filters for the accel / gyro + static constexpr auto filter_bw = icm42607::SensorFilterBandwidth::BW_16_HZ; + if (!imu_->set_accelerometer_filter(filter_bw, ec)) { + logger_.error("Failed to set accel filter: {}", ec.message()); + return false; + } + if (!imu_->set_gyroscope_filter(filter_bw, ec)) { + logger_.error("Failed to set gyro filter: {}", ec.message()); + return false; + } + + return true; +} + +std::shared_ptr EspBox::imu() const { return imu_; } diff --git a/components/filters/CMakeLists.txt b/components/filters/CMakeLists.txt index 5c34cb7f8..1c2ed7b59 100644 --- a/components/filters/CMakeLists.txt +++ b/components/filters/CMakeLists.txt @@ -1,4 +1,4 @@ idf_component_register( INCLUDE_DIRS "include" SRC_DIRS "src" - REQUIRES esp_timer format esp-dsp) + REQUIRES esp_timer format esp-dsp math) diff --git a/components/filters/include/complementary_filter.hpp b/components/filters/include/complementary_filter.hpp new file mode 100644 index 000000000..811ffc5a6 --- /dev/null +++ b/components/filters/include/complementary_filter.hpp @@ -0,0 +1,78 @@ +#pragma once + +#include + +#include "fast_math.hpp" + +namespace espp { +/// Complementary filter for estimating pitch and roll angles from +/// accelerometer and gyroscope readings. +/// The filter is defined by the following equation: +/// angle = alpha * (angle + gyro * dt) + (1 - alpha) * accel +/// where: +/// - angle is the estimated angle, +/// - alpha is the filter coefficient (0 < alpha < 1), +/// - gyro is the gyroscope reading, +/// - accel is the accelerometer reading, +/// - dt is the time step. +class ComplementaryFilter { +public: + /// Constructor + /// \param alpha Filter coefficient (0 < alpha < 1) + explicit ComplementaryFilter(float alpha = 0.98) + : alpha(alpha) + , pitch(0.0f) + , roll(0.0f) {} + + /// Update the filter with accelerometer and gyroscope readings. + /// \param accel Accelerometer readings (m/s^2) + /// \param gyro Gyroscope readings (degrees/s) + /// \param dt Time step (s) + /// \note The accelerometer and gyroscope readings must be in the + /// same coordinate system. + void update(const std::span &accel, const std::span &gyro, + float dt) { + update(accel[0], accel[1], accel[2], gyro[0], gyro[1], gyro[2], dt); + } + + /// Update the filter with accelerometer and gyroscope readings. + /// \param ax Accelerometer x-axis reading (m/s^2) + /// \param ay Accelerometer y-axis reading (m/s^2) + /// \param az Accelerometer z-axis reading (m/s^2) + /// \param gx Gyroscope x-axis reading (degrees/s) + /// \param gy Gyroscope y-axis reading (degrees/s) + /// \param gz Gyroscope z-axis reading (degrees/s) + /// \param dt Time step (s) + /// \note The accelerometer and gyroscope readings must be in the + /// same coordinate system. + void update(float ax, float ay, float az, float gx, float gy, float gz, float dt) { + // Convert gyroscope readings from degrees/s to radians/s + gx = gx * M_PI / 180.0f; + gy = gy * M_PI / 180.0f; + + // Compute pitch and roll from accelerometer (degrees) + float accelPitch = atan2(ay, sqrt(ax * ax + az * az)) * 180.0f / M_PI; + float accelRoll = atan2(-ax, az) * 180.0f / M_PI; + + // Integrate gyroscope readings + float gyroPitch = pitch + gy * dt; + float gyroRoll = roll + gx * dt; + + // Apply complementary filter + pitch = alpha * gyroPitch + (1 - alpha) * accelPitch; + roll = alpha * gyroRoll + (1 - alpha) * accelRoll; + } + + /// Get the estimated pitch angle (degrees) + /// \return The estimated pitch angle + float get_pitch() const { return pitch; } + + /// Get the estimated roll angle (degrees) + /// \return The estimated roll angle + float get_roll() const { return roll; } + +protected: + float alpha; + float pitch, roll; +}; // class ComplimentaryFilter +} // namespace espp diff --git a/components/filters/include/kalman_filter.hpp b/components/filters/include/kalman_filter.hpp new file mode 100644 index 000000000..1cf9ad9a9 --- /dev/null +++ b/components/filters/include/kalman_filter.hpp @@ -0,0 +1,161 @@ +#pragma once + +#include +#include + +#include "fast_math.hpp" + +namespace espp { +/// Kalman Filter for single variable state estimation +/// @tparam N Number of states +/// +/// This class implements a simple Kalman filter for estimating the state of a +/// variable, such as the orientation of a system. The filter is based on the +/// following state-space model: +/// \f[ +/// X' = X + U \cdot dt +/// \f] +/// \f[ +/// P' = P + Q +/// \f] +/// \f[ +/// Y = Z - X +/// \f] +/// \f[ +/// K = P / (P + R) +/// \f] +/// \f[ +/// X = X + K \cdot Y +/// \f] +/// \f[ +/// P = (1 - K) \cdot P +/// \f] +/// where: +/// - \f$X\f$ is the state vector +/// - \f$P\f$ is the covariance matrix +/// - \f$Q\f$ is the process noise +/// - \f$R\f$ is the measurement noise +/// - \f$U\f$ is the control input +/// - \f$dt\f$ is the time step +/// - \f$Z\f$ is the measurement +template class KalmanFilter { +public: + /// Constructor + KalmanFilter() { + X.fill(0.0f); // Initialize state vector + P.fill({}); // Initialize covariance matrix + + for (size_t i = 0; i < N; i++) { + P[i][i] = 1.0f; // Initial covariance + Q[i][i] = 0.001f; // Process noise + R[i][i] = 0.01f; // Measurement noise + } + } + + /// Set process noise + /// @param q Process noise + /// @note The process noise is the uncertainty in the model. It is used to + /// compute the error covariance, which determines how much the + /// prediction is trusted. A higher process noise means that the + /// prediction is less trusted, and the filter relies more on the + /// measurement. A lower process noise means that the prediction is + /// more trusted, and the filter relies less on the measurement. + void set_process_noise(float q) { + for (size_t i = 0; i < N; i++) + Q[i][i] = q; + } + + /// Set process noise + /// @param q Process noise vector + void set_process_noise(const std::array &q) { + for (size_t i = 0; i < N; i++) + Q[i][i] = q[i]; + } + + /// Set measurement noise + /// @param r Measurement noise + /// @note The measurement noise is the uncertainty in the measurement. It is + /// used to compute the Kalman Gain, which determines how much the + /// measurement should affect the state estimate. + void set_measurement_noise(float r) { + for (size_t i = 0; i < N; i++) + R[i][i] = r; + } + + /// Set measurement noise + /// @param r Measurement noise vector + void set_measurement_noise(const std::array &r) { + for (size_t i = 0; i < N; i++) + R[i][i] = r[i]; + } + + /// Predict next state + /// @param U Control input + /// @param dt Time step + /// @note The prediction step estimates the state at the next time step + /// based on the current state and the control input. The control + /// input is used to model the effect of the control on the state. The + /// time step is the time between measurements. + void predict(const std::array &U, float dt) { + // Predict next state: X' = X + U * dt + for (size_t i = 0; i < N; i++) { + X[i] += U[i] * dt; + } + + // Update covariance: P = P + Q + for (size_t i = 0; i < N; i++) { + for (size_t j = 0; j < N; j++) { + P[i][j] += Q[i][j]; + } + } + } + + /// Update state estimate + /// @param Z Measurement + /// @note The correction step updates the state estimate based on the + /// measurement. The measurement is used to compute the Kalman Gain, + /// which determines how much the measurement should affect the state + /// estimate. The Kalman Gain is used to update the state estimate and + /// the error covariance. + void update(const std::array &Z) { + std::array Y; // Measurement residual + + // Compute residual: Y = Z - X + for (size_t i = 0; i < N; i++) { + Y[i] = Z[i] - X[i]; + } + + // Compute Kalman Gain: K = P / (P + R) + for (size_t i = 0; i < N; i++) { + for (size_t j = 0; j < N; j++) { + K[i][j] = P[i][j] / (P[i][j] + R[i][j]); + } + } + + // Update state: X = X + K * Y + for (size_t i = 0; i < N; i++) { + X[i] += K[i][i] * Y[i]; + } + + // Update error covariance: P = (1 - K) * P + for (size_t i = 0; i < N; i++) { + for (size_t j = 0; j < N; j++) { + P[i][j] = (1 - K[i][i]) * P[i][j]; + } + } + } + + /// Get state estimate + /// @return State estimate + /// @note The state estimate is the current estimate of the state based on + /// the measurements. + const std::array &get_state() const { return X; } + +protected: + std::array X; // State vector + std::array, N> P; // Covariance matrix + std::array, N> Q; // Process noise + std::array, N> R; // Measurement noise + std::array, N> K; // Kalman Gain +}; // class KalmanFilter +} // namespace espp diff --git a/components/filters/include/madgwick_filter.hpp b/components/filters/include/madgwick_filter.hpp new file mode 100644 index 000000000..06b0876d5 --- /dev/null +++ b/components/filters/include/madgwick_filter.hpp @@ -0,0 +1,252 @@ +#pragma once + +#include + +#include "fast_math.hpp" + +namespace espp { +/// Madgwick filter for IMU data Based on: +/// https://x-io.co.uk/open-source-imu-and-ahrs-algorithms/ (now +/// https://github.com/xioTechnologies/Fusion) +class MadgwickFilter { +public: + /// @brief Constructor + /// @param beta Filter gain + explicit MadgwickFilter(float beta = 0.1f) + : beta(beta) + , q0(1.0f) + , q1(0.0f) + , q2(0.0f) + , q3(0.0f) {} + + /// @brief Update the filter with new data + /// @param dt Time step in seconds + /// @param ax Accelerometer x value in g + /// @param ay Accelerometer y value in g + /// @param az Accelerometer z value in g + /// @param gx Gyroscope x value in rad/s + /// @param gy Gyroscope y value in rad/s + /// @param gz Gyroscope z value in rad/s + /// @param mx Magnetometer x value in uT + /// @param my Magnetometer y value in uT + /// @param mz Magnetometer z value in uT + /// @note Accelerometer values should be normalized + /// @note Gyroscope values should be in rad/s + /// @note Magnetometer values should be normalized + /// @note If magnetometer values are not available (all 0), this function will + /// fallback to using only accelerometer and gyroscope values + void update(float dt, float ax, float ay, float az, float gx, float gy, float gz, float mx, + float my, float mz) { + // Use IMU algorithm if magnetometer measurement invalid (avoids NaN in magnetometer + // normalisation) + if ((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) { + update(dt, ax, ay, az, gx, gy, gz); + return; + } + + float recipNorm; + float qDot1, qDot2, qDot3, qDot4; + + // Rate of change of quaternion from gyroscope + qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); + qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); + qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); + qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); + + // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer + // normalisation) + if (!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { + float s0, s1, s2, s3; + float hx, hy; + float _2q0mx, _2q0my, _2q0mz, _2q1mx, _2bx, _2bz, _4bx, _4bz, _2q0, _2q1, _2q2, _2q3, _2q0q2, + _2q2q3, q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3; + + // Normalise accelerometer measurement + recipNorm = fast_inv_sqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; + + // Normalise magnetometer measurement + recipNorm = fast_inv_sqrt(mx * mx + my * my + mz * mz); + mx *= recipNorm; + my *= recipNorm; + mz *= recipNorm; + + // Auxiliary variables to avoid repeated arithmetic + _2q0mx = 2.0f * q0 * mx; + _2q0my = 2.0f * q0 * my; + _2q0mz = 2.0f * q0 * mz; + _2q1mx = 2.0f * q1 * mx; + _2q0 = 2.0f * q0; + _2q1 = 2.0f * q1; + _2q2 = 2.0f * q2; + _2q3 = 2.0f * q3; + _2q0q2 = 2.0f * q0 * q2; + _2q2q3 = 2.0f * q2 * q3; + q0q0 = q0 * q0; + q0q1 = q0 * q1; + q0q2 = q0 * q2; + q0q3 = q0 * q3; + q1q1 = q1 * q1; + q1q2 = q1 * q2; + q1q3 = q1 * q3; + q2q2 = q2 * q2; + q2q3 = q2 * q3; + q3q3 = q3 * q3; + + // Reference direction of Earth's magnetic field + hx = mx * q0q0 - _2q0my * q3 + _2q0mz * q2 + mx * q1q1 + _2q1 * my * q2 + _2q1 * mz * q3 - + mx * q2q2 - mx * q3q3; + hy = _2q0mx * q3 + my * q0q0 - _2q0mz * q1 + _2q1mx * q2 - my * q1q1 + my * q2q2 + + _2q2 * mz * q3 - my * q3q3; + _2bx = sqrt(hx * hx + hy * hy); + _2bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + _2q2 * my * q3 - + mz * q2q2 + mz * q3q3; + _4bx = 2.0f * _2bx; + _4bz = 2.0f * _2bz; + + // Gradient decent algorithm corrective step + s0 = -_2q2 * (2.0f * q1q3 - _2q0q2 - ax) + _2q1 * (2.0f * q0q1 + _2q2q3 - ay) - + _2bz * q2 * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + + (-_2bx * q3 + _2bz * q1) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + + _2bx * q2 * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); + s1 = _2q3 * (2.0f * q1q3 - _2q0q2 - ax) + _2q0 * (2.0f * q0q1 + _2q2q3 - ay) - + 4.0f * q1 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + + _2bz * q3 * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + + (_2bx * q2 + _2bz * q0) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + + (_2bx * q3 - _4bz * q1) * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); + s2 = -_2q0 * (2.0f * q1q3 - _2q0q2 - ax) + _2q3 * (2.0f * q0q1 + _2q2q3 - ay) - + 4.0f * q2 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + + (-_4bx * q2 - _2bz * q0) * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + + (_2bx * q1 + _2bz * q3) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + + (_2bx * q0 - _4bz * q2) * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); + s3 = _2q1 * (2.0f * q1q3 - _2q0q2 - ax) + _2q2 * (2.0f * q0q1 + _2q2q3 - ay) + + (-_4bx * q3 + _2bz * q1) * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + + (-_2bx * q0 + _2bz * q2) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + + _2bx * q1 * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz); + recipNorm = fast_inv_sqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude + s0 *= recipNorm; + s1 *= recipNorm; + s2 *= recipNorm; + s3 *= recipNorm; + + // Apply feedback step + qDot1 -= beta * s0; + qDot2 -= beta * s1; + qDot3 -= beta * s2; + qDot4 -= beta * s3; + } + + // Integrate rate of change of quaternion to yield quaternion + q0 += qDot1 * dt; + q1 += qDot2 * dt; + q2 += qDot3 * dt; + q3 += qDot4 * dt; + + // Normalise quaternion + recipNorm = fast_inv_sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); + q0 *= recipNorm; + q1 *= recipNorm; + q2 *= recipNorm; + q3 *= recipNorm; + } + + /// @brief Update the filter with new data + /// @param dt Time step in seconds + /// @param ax Accelerometer x value in g + /// @param ay Accelerometer y value in g + /// @param az Accelerometer z value in g + /// @param gx Gyroscope x value in rad/s + /// @param gy Gyroscope y value in rad/s + /// @param gz Gyroscope z value in rad/s + /// @note Accelerometer values should be normalized + /// @note Gyroscope values should be in rad/s + void update(float dt, float ax, float ay, float az, float gx, float gy, float gz) { + float recipNorm; + float qDot1, qDot2, qDot3, qDot4; + + // Rate of change of quaternion from gyroscope + qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz); + qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy); + qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx); + qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx); + + // Compute feedback only if accelerometer measurement valid (avoids NaN in accelerometer + // normalisation) + if (!((ax == 0.0f) && (ay == 0.0f) && (az == 0.0f))) { + float s0, s1, s2, s3; + float _2q0, _2q1, _2q2, _2q3, _4q0, _4q1, _4q2, _8q1, _8q2, q0q0, q1q1, q2q2, q3q3; + + // Normalise accelerometer measurement + recipNorm = fast_inv_sqrt(ax * ax + ay * ay + az * az); + ax *= recipNorm; + ay *= recipNorm; + az *= recipNorm; + + // Auxiliary variables to avoid repeated arithmetic + _2q0 = 2.0f * q0; + _2q1 = 2.0f * q1; + _2q2 = 2.0f * q2; + _2q3 = 2.0f * q3; + _4q0 = 4.0f * q0; + _4q1 = 4.0f * q1; + _4q2 = 4.0f * q2; + _8q1 = 8.0f * q1; + _8q2 = 8.0f * q2; + q0q0 = q0 * q0; + q1q1 = q1 * q1; + q2q2 = q2 * q2; + q3q3 = q3 * q3; + + // Gradient decent algorithm corrective step + s0 = _4q0 * q2q2 + _2q2 * ax + _4q0 * q1q1 - _2q1 * ay; + s1 = _4q1 * q3q3 - _2q3 * ax + 4.0f * q0q0 * q1 - _2q0 * ay - _4q1 + _8q1 * q1q1 + + _8q1 * q2q2 + _4q1 * az; + s2 = 4.0f * q0q0 * q2 + _2q0 * ax + _4q2 * q3q3 - _2q3 * ay - _4q2 + _8q2 * q1q1 + + _8q2 * q2q2 + _4q2 * az; + s3 = 4.0f * q1q1 * q3 - _2q1 * ax + 4.0f * q2q2 * q3 - _2q2 * ay; + recipNorm = fast_inv_sqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude + s0 *= recipNorm; + s1 *= recipNorm; + s2 *= recipNorm; + s3 *= recipNorm; + + // Apply feedback step + qDot1 -= beta * s0; + qDot2 -= beta * s1; + qDot3 -= beta * s2; + qDot4 -= beta * s3; + } + + // Integrate rate of change of quaternion to yield quaternion + q0 += qDot1 * dt; + q1 += qDot2 * dt; + q2 += qDot3 * dt; + q3 += qDot4 * dt; + + // Normalise quaternion + recipNorm = fast_inv_sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); + q0 *= recipNorm; + q1 *= recipNorm; + q2 *= recipNorm; + q3 *= recipNorm; + } + + /// @brief Get the current quaternion values as euler angles + /// @param[out] pitch Pitch angle in degrees + /// @param[out] roll Roll angle in degrees + /// @param[out] yaw Yaw angle in degrees + /// @note Euler angles are in degrees + void get_euler(float &pitch, float &roll, float &yaw) const { + pitch = + atan2(2.0f * (q0 * q1 + q2 * q3), q0 * q0 - q1 * q1 - q2 * q2 + q3 * q3) * 180.0f / M_PI; + roll = asin(-2.0f * (q1 * q3 - q0 * q2)) * 180.0f / M_PI; + yaw = atan2(2.0f * (q1 * q2 + q0 * q3), q0 * q0 + q1 * q1 - q2 * q2 - q3 * q3) * 180.0f / M_PI; + } + +protected: + float beta; // Filter gain + float q0, q1, q2, q3; // Quaternion values +}; +} // namespace espp diff --git a/components/icm42607/CMakeLists.txt b/components/icm42607/CMakeLists.txt new file mode 100644 index 000000000..3d35d0937 --- /dev/null +++ b/components/icm42607/CMakeLists.txt @@ -0,0 +1,4 @@ +idf_component_register( + INCLUDE_DIRS "include" + REQUIRES "base_peripheral" "math" + ) diff --git a/components/icm42607/example/CMakeLists.txt b/components/icm42607/example/CMakeLists.txt new file mode 100644 index 000000000..59bb5d171 --- /dev/null +++ b/components/icm42607/example/CMakeLists.txt @@ -0,0 +1,21 @@ +# The following 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.5) + +include($ENV{IDF_PATH}/tools/cmake/project.cmake) + +# add the component directories that we want to use +set(EXTRA_COMPONENT_DIRS + "../../../components/" +) + +set( + COMPONENTS + "main esptool_py i2c icm42607 filters" + CACHE STRING + "List of components to include" + ) + +project(icm42607_example) + +set(CMAKE_CXX_STANDARD 20) diff --git a/components/icm42607/example/README.md b/components/icm42607/example/README.md new file mode 100644 index 000000000..2135a3651 --- /dev/null +++ b/components/icm42607/example/README.md @@ -0,0 +1,35 @@ +# ICM42607 Example + +This example shows how to use the `espp::Icm42607` component to initialize and +communicate with an ICM42607 / ICM42670 6-axis IMU. + +![CleanShot 2025-03-04 at 15 14 10](https://github.com/user-attachments/assets/131e102c-bcab-4732-8593-aa0c56aaebd5) + +## How to use example + +### Hardware Required + +This example is designed to run on the ESP32-S3-BOX or ESP32-S3-BOX-3, as they +have on-board IMUs. + +### Build and Flash + +Build the project and flash it to the board, then run monitor tool to view +serial output: + +``` +idf.py -p PORT flash monitor +``` + +(Replace PORT with the name of the serial port to use.) + +(To exit the serial monitor, type ``Ctrl-]``.) + +See the Getting Started Guide for full steps to configure and use ESP-IDF to build projects. + +## Example Output + +![CleanShot 2025-03-04 at 15 15 45](https://github.com/user-attachments/assets/ac2db65c-8be5-4a31-820c-2f7e88cc8ea5) + +Running with `esp-cpp/uart-serial-plotter`: +![CleanShot 2025-03-04 at 15 14 10](https://github.com/user-attachments/assets/131e102c-bcab-4732-8593-aa0c56aaebd5) diff --git a/components/icm42607/example/main/CMakeLists.txt b/components/icm42607/example/main/CMakeLists.txt new file mode 100644 index 000000000..a941e22ba --- /dev/null +++ b/components/icm42607/example/main/CMakeLists.txt @@ -0,0 +1,2 @@ +idf_component_register(SRC_DIRS "." + INCLUDE_DIRS ".") diff --git a/components/icm42607/example/main/Kconfig.projbuild b/components/icm42607/example/main/Kconfig.projbuild new file mode 100644 index 000000000..73c197c83 --- /dev/null +++ b/components/icm42607/example/main/Kconfig.projbuild @@ -0,0 +1,40 @@ +menu "Example Configuration" + + choice EXAMPLE_HARDWARE + prompt "Hardware" + default EXAMPLE_HARDWARE_ESP_BOX + help + Select the hardware to run this example on. + + config EXAMPLE_HARDWARE_ESP_BOX + depends on IDF_TARGET_ESP32S3 + bool "ESP32-S3-BOX or ESP32-S3-BOX-3" + + config EXAMPLE_HARDWARE_CUSTOM + bool "Custom" + endchoice + + config EXAMPLE_I2C_SCL_GPIO + int "SCL GPIO Num" + range 0 50 + default 18 if EXAMPLE_HARDWARE_ESP_BOX + default 19 if EXAMPLE_HARDWARE_CUSTOM + help + GPIO number for I2C Master clock line. + + config EXAMPLE_I2C_SDA_GPIO + int "SDA GPIO Num" + range 0 50 + default 8 if EXAMPLE_HARDWARE_ESP_BOX + default 22 if EXAMPLE_HARDWARE_CUSTOM + help + GPIO number for I2C Master data line. + + config EXAMPLE_I2C_CLOCK_SPEED_HZ + int "I2C Clock Speed" + range 100 1000000 + default 400000 + help + I2C clock speed in Hz. + +endmenu diff --git a/components/icm42607/example/main/icm42607_example.cpp b/components/icm42607/example/main/icm42607_example.cpp new file mode 100644 index 000000000..16c364772 --- /dev/null +++ b/components/icm42607/example/main/icm42607_example.cpp @@ -0,0 +1,195 @@ +#include +#include + +#include "i2c.hpp" +#include "icm42607.hpp" +#include "kalman_filter.hpp" +#include "madgwick_filter.hpp" + +using namespace std::chrono_literals; + +extern "C" void app_main(void) { + espp::Logger logger({.tag = "ICM42607 Example", .level = espp::Logger::Verbosity::INFO}); + logger.info("Starting example!"); + + //! [icm42607 example] + using Imu = espp::Icm42607; + + // make the i2c we'll use to communicate + static constexpr auto i2c_port = I2C_NUM_0; + static constexpr auto i2c_clock_speed = CONFIG_EXAMPLE_I2C_CLOCK_SPEED_HZ; + static constexpr gpio_num_t i2c_sda = (gpio_num_t)CONFIG_EXAMPLE_I2C_SDA_GPIO; + static constexpr gpio_num_t i2c_scl = (gpio_num_t)CONFIG_EXAMPLE_I2C_SCL_GPIO; + espp::I2c i2c({.port = i2c_port, + .sda_io_num = i2c_sda, + .scl_io_num = i2c_scl, + .sda_pullup_en = GPIO_PULLUP_ENABLE, + .scl_pullup_en = GPIO_PULLUP_ENABLE, + .clk_speed = i2c_clock_speed}); + + // make the IMU config + Imu::Config config{ + .device_address = Imu::DEFAULT_ADDRESS, + .write = std::bind(&espp::I2c::write, &i2c, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3), + .read = std::bind(&espp::I2c::read, &i2c, std::placeholders::_1, std::placeholders::_2, + std::placeholders::_3), + .imu_config = + { + .accelerometer_range = Imu::AccelerometerRange::RANGE_2G, + .accelerometer_odr = Imu::AccelerometerODR::ODR_400_HZ, + .gyroscope_range = Imu::GyroscopeRange::RANGE_2000DPS, + .gyroscope_odr = Imu::GyroscopeODR::ODR_400_HZ, + }, + .auto_init = true, + }; + + // create the IMU + logger.info("Creating IMU"); + Imu imu(config); + std::error_code ec; + + // turn on DMP + logger.info("Turning on DMP"); + if (!imu.set_dmp_power_save(false, ec)) { + logger.error("Failed to set DMP power save mode: {}", ec.message()); + return; + } + + // initialize the DMP + logger.info("Initializing DMP"); + if (!imu.dmp_initialize(ec)) { + logger.error("Failed to initialize DMP: {}", ec.message()); + return; + } + + // set the DMP output data rate + logger.info("Setting DMP output data rate (ODR)"); + if (!imu.set_dmp_odr(espp::icm42607::DmpODR::ODR_25_HZ, ec)) { + logger.error("Failed to set DMP ODR: {}", ec.message()); + return; + } + + // set filters for the accel / gyro + logger.info("Setting accel and gyro filters"); + static constexpr auto filter_bw = espp::icm42607::SensorFilterBandwidth::BW_16_HZ; + if (!imu.set_accelerometer_filter(filter_bw, ec)) { + logger.error("Failed to set accel filter: {}", ec.message()); + return; + } + if (!imu.set_gyroscope_filter(filter_bw, ec)) { + logger.error("Failed to set gyro filter: {}", ec.message()); + return; + } + + // make a task to read out the IMU data and print it to console + espp::Task imu_task( + {.callback = [&imu](std::mutex &m, std::condition_variable &cv) -> bool { + // sleep first in case we don't get IMU data and need to exit early + { + std::unique_lock lock(m); + cv.wait_for(lock, 10ms); + } + + auto now = esp_timer_get_time(); // time in microseconds + static auto t0 = now; + auto t1 = now; + float dt = (t1 - t0) / 1'000'000.0f; // convert us to s + t0 = t1; + + std::error_code ec; + // get accel + auto accel = imu.get_accelerometer(ec); + if (ec) { + return false; + } + auto gyro = imu.get_gyroscope(ec); + if (ec) { + return false; + } + auto temp = imu.get_temperature(ec); + if (ec) { + return false; + } + + // print time and raw IMU data + std::string text = ""; + text += fmt::format("{:.3f},", now / 1'000'000.0f); + text += fmt::format("{:02.3f},{:02.3f},{:02.3f},", accel.x, accel.y, accel.z); + text += fmt::format("{:03.3f},{:03.3f},{:03.3f},", gyro.x, gyro.y, gyro.z); + text += fmt::format("{:02.1f},", temp); + + float roll = 0, pitch = 0; + + // with only the accelerometer + gyroscope, we can't get yaw :( + static constexpr float angle_noise = 0.001f; + static constexpr float rate_noise = 0.1f; + static espp::KalmanFilter<2> kf; + kf.set_process_noise(rate_noise); + kf.set_measurement_noise(angle_noise); + static constexpr float beta = 0.1f; // higher = more accelerometer, lower = more gyro + static espp::MadgwickFilter f(beta); + + f.update(dt, accel.x, accel.y, accel.z, gyro.x * M_PI / 180.0f, gyro.y * M_PI / 180.0f, + gyro.z * M_PI / 180.0f); + float yaw; // ignore / unused since we only have 6-axis + f.get_euler(roll, pitch, yaw); + roll *= M_PI / 180.0f; + pitch *= M_PI / 180.0f; + + float vx = sin(pitch); + float vy = -cos(pitch) * sin(roll); + float vz = -cos(pitch) * cos(roll); + + // print madgwick filter outputs + text += fmt::format("{:03.3f},{:03.3f},", roll, pitch); + text += fmt::format("{:03.3f},{:03.3f},{:03.3f},", vx, vy, vz); + + // Apply Kalman filter + float accelPitch = atan2(-accel.x, sqrt(accel.y * accel.y + accel.z * accel.z)); + float accelRoll = atan2(accel.y, accel.z); + kf.predict({float(gyro.x * M_PI / 180.0f), float(gyro.y * M_PI / 180.0f)}, dt); + kf.update({accelPitch, accelRoll}); + std::tie(pitch, roll) = kf.get_state(); + + vx = sin(pitch); + vy = -cos(pitch) * sin(roll); + vz = -cos(pitch) * cos(roll); + + // print kalman filter outputs + text += fmt::format("{:03.3f},{:03.3f},", roll, pitch); + text += fmt::format("{:03.3f},{:03.3f},{:03.3f}", vx, vy, vz); + + fmt::print("{}\n", text); + + return false; + }, + .task_config = { + .name = "IMU", + .stack_size_bytes = 6 * 1024, + .priority = 10, + .core_id = 0, + }}); + + // print the header for the IMU data (for plotting) + fmt::print("% Time (s), " + // raw IMU data (accel, gyro, temp) + "Accel X (m/s^2), Accel Y (m/s^2), Accel Z (m/s^2), " + "Gyro X (rad/s), Gyro Y (rad/s), Gyro Z (rad/s), " + "Temp (C), " + // madgwick filter outputs + "Madgwick Roll (rad), Madgwick Pitch (rad), " + "Madgwick Gravity X, Madgwick Gravity Y, Madgwick Gravity Z, " + // kalman filter outputs + "Kalman Roll (rad), Kalman Pitch (rad), " + "Kalman Gravity X, Kalman Gravity Y, Kalman Gravity Z\n"); + + logger.info("Starting IMU task"); + imu_task.start(); + + // loop forever + while (true) { + std::this_thread::sleep_for(1s); + } + //! [icm42607 example] +} diff --git a/components/icm42607/example/sdkconfig.defaults b/components/icm42607/example/sdkconfig.defaults new file mode 100644 index 000000000..b579842de --- /dev/null +++ b/components/icm42607/example/sdkconfig.defaults @@ -0,0 +1,26 @@ +CONFIG_IDF_TARGET="esp32s3" + +CONFIG_FREERTOS_HZ=1000 + +# set compiler optimization level to -O2 (compile for performance) +CONFIG_COMPILER_OPTIMIZATION_PERF=y + +CONFIG_ESPTOOLPY_FLASHSIZE_16MB=y +CONFIG_ESPTOOLPY_FLASHSIZE="16MB" +CONFIG_ESPTOOLPY_FLASHMODE_QIO=y # over twice as fast as DIO + +# ESP32-specific +# +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ_240=y +CONFIG_ESP_DEFAULT_CPU_FREQ_MHZ=240 + +# Common ESP-related +# +CONFIG_ESP_SYSTEM_EVENT_TASK_STACK_SIZE=4096 +CONFIG_ESP_MAIN_TASK_STACK_SIZE=16384 + +# Set esp-timer task stack size to 6KB +CONFIG_ESP_TIMER_TASK_STACK_SIZE=6144 + +# set the functions into IRAM +CONFIG_SPI_MASTER_IN_IRAM=y diff --git a/components/icm42607/include/icm42607.hpp b/components/icm42607/include/icm42607.hpp new file mode 100644 index 000000000..a9e220c9d --- /dev/null +++ b/components/icm42607/include/icm42607.hpp @@ -0,0 +1,700 @@ +#pragma once + +#include "base_peripheral.hpp" + +#include "icm42607_detail.hpp" + +namespace espp { +/// @brief Class for the ICM42607 6-axis motion sensor +/// @tparam Interface The interface type of the ICM42607 +/// +/// @note The ICM42607 is a 6-axis motion sensor that can be interfaced with +/// either I2C or SPI. +/// +/// @note The Icm42607 can work with both the Icm42607 and Icm42670, as they +/// are the same sensor. +/// +/// The ICM42607 has a 3-axis gyroscope and a 3-axis accelerometer. The +/// ICM42607 has a 16-bit ADC for the gyroscope and a 16-bit ADC for the +/// accelerometer. The gyroscope has a full-scale range of up to ±2000°/s and +/// the accelerometer has a full-scale range of up to ±16g. +/// +/// The ICM42607 has a FIFO buffer that can store up to 2.25 kilobytes of +/// data. The FIFO buffer can be configured to store gyroscope data, +/// accelerometer data, or both. The FIFO buffer can be configured to store +/// data in either FIFO mode or stream mode. In FIFO mode, the FIFO buffer +/// stores data until the buffer is full, at which point the FIFO buffer stops +/// storing data. In stream mode, the FIFO buffer stores data continuously, +/// overwriting the oldest data when the buffer is full. +/// +/// The ICM42607 has a Digital Motion Processor (DMP) that can be used to +/// process the data from the gyroscope and accelerometer. The DMP can be used +/// to calculate the orientation of the ICM42607, the linear acceleration of +/// the ICM42607, and the angular velocity of the ICM42607. The DMP can also +/// be used to detect motion events, such as tap events, shake events, and +/// orientation events. +/// +/// The ICM42607 has a built-in temperature sensor that can be used to measure +/// the temperature of the ICM42607. The temperature sensor has a resolution +/// of 0.5°C and an accuracy of ±2°C. +/// +/// It supports low-noise 6-axis measurement with a current consumption at +/// only 0.55 mA and a sleep mode current consumption of only 3.5 µA. +/// +/// For more information see, the datasheet: +/// https://invensense.tdk.com/wp-content/uploads/2021/07/ds-000451_icm-42670-p-datasheet.pdf +/// +/// \section icm42607_example Example +/// \snippet icm42607_example.cpp icm42607 example +template +class Icm42607 : public espp::BasePeripheral { + // Since the BasePeripheral is a dependent base class (e.g. its template + // parameters depend on our template parameters), we need to use the `using` + // keyword to bring in the functions / members we want to use, otherwise we + // have to either use `this->` or explicitly scope each call, which clutters + // the code / is annoying. This is needed because of the two phases of name + // lookups for templates. + using BasePeripheral::set_address; + using BasePeripheral::set_write; + using BasePeripheral::set_read; + using BasePeripheral::write_u8_to_register; + using BasePeripheral::write_many_to_register; + using BasePeripheral::read_u8_from_register; + using BasePeripheral::read_u16_from_register; + using BasePeripheral::read_many_from_register; + using BasePeripheral::clear_bits_in_register; + using BasePeripheral::set_bits_in_register; + using BasePeripheral::set_bits_in_register_by_mask; + using BasePeripheral::read; + using BasePeripheral::logger_; + +public: + static constexpr uint8_t DEFAULT_ADDRESS = + 0x68; ///< Default I2C address of the ICM42607 with AD0 low + static constexpr uint8_t DEFAULT_ADDRESS_AD0_HIGH = + 0x69; ///< Default I2C address of the ICM42607 with AD0 high + + using FifoMode = icm42607::FifoMode; ///< FIFO mode + using AccelerometerRange = icm42607::AccelerometerRange; ///< Accelerometer range + using AccelerometerPowerMode = icm42607::AccelerometerPowerMode; ///< Accelerometer power mode + using AccelerometerODR = icm42607::AccelerometerODR; ///< Accelerometer output data rate + using GyroscopeRange = icm42607::GyroscopeRange; ///< Gyroscope range + using GyroscopePowerMode = icm42607::GyroscopePowerMode; ///< Gyroscope power mode + using GyroscopeODR = icm42607::GyroscopeODR; ///< Gyroscope output data rate + using DmpODR = icm42607::DmpODR; ///< DMP output data rate + using TemperatureFilterBandwidth = + icm42607::TemperatureFilterBandwidth; ///< Temperature filter bandwidth + using SensorFilterBandwidth = icm42607::SensorFilterBandwidth; ///< Sensor filter bandwidth + using ImuConfig = icm42607::ImuConfig; ///< IMU configuration + using RawValue = icm42607::RawValue; ///< Raw IMU data + using Value = icm42607::Value; ///< IMU data + using ComplimentaryAngle = icm42607::ComplimentaryAngle; ///< Complimentary angle + using InterruptDriveMode = icm42607::InterruptDriveMode; ///< Interrupt drive mode + using InterruptPolarity = icm42607::InterruptPolarity; ///< Interrupt polarity + using InterruptMode = icm42607::InterruptMode; ///< Interrupt mode + using InterruptConfig = icm42607::InterruptConfig; ///< Interrupt configuration + + /// Configuration struct for the ICM42607 + struct Config { + uint8_t device_address = DEFAULT_ADDRESS; ///< I2C address of the ICM42607 + BasePeripheral::write_fn write = + nullptr; ///< Write function + BasePeripheral::read_fn read = + nullptr; ///< Read function + ImuConfig imu_config; ///< IMU configuration + bool auto_init{true}; ///< Automatically initialize the ICM42607 + Logger::Verbosity log_level{Logger::Verbosity::WARN}; ///< Log level + }; + + /// Constructor + /// @param config The configuration + explicit Icm42607(const Config &config) + : BasePeripheral({}, "Icm42607", + config.log_level) + , imu_config_(config.imu_config) { + if constexpr (Interface == icm42607::Interface::I2C) { + set_address(config.device_address); + } + set_write(config.write); + set_read(config.read); + if (config.auto_init) { + std::error_code ec; + init(ec); + } + } + + /// Initialize the ICM42607 + /// @param ec The error code to set if an error occurs + /// @return True if the ICM42607 was initialized successfully, false otherwise + bool init(std::error_code &ec) { + auto device_id = get_device_id(ec); + if (device_id != ICM42607_ID && device_id != ICM42670_ID) { + logger_.error("Invalid device ID: 0x{:02X}", device_id); + return false; + } + + // set the configuration + if (!set_config(imu_config_, ec)) { + return false; + } + + // turn on the accelerometer + if (!set_accelerometer_power_mode(AccelerometerPowerMode::LOW_NOISE, ec)) { + return false; + } + + // turn on the gyroscope + if (!set_gyroscope_power_mode(GyroscopePowerMode::LOW_NOISE, ec)) { + return false; + } + + return true; + } + + /// Get the device ID + /// @param ec The error code to set if an error occurs + /// @return The device ID + uint8_t get_device_id(std::error_code &ec) { + return read_u8_from_register(static_cast(Register::WHO_AM_I), ec); + } + + /// Set the IMU configuration + /// @param imu_config The IMU configuration + /// @param ec The error code to set if an error occurs + /// @return True if the configuration was set successfully, false otherwise + bool set_config(const ImuConfig &imu_config, std::error_code &ec) { + // save the config + imu_config_ = imu_config; + + // the config is set as two bytes containing the configuration for the + // accelerometer and gyroscope (full scale range and output data rate) + uint8_t data[2] = {// first byte is gyro fs + odr + uint8_t((static_cast(imu_config.gyroscope_range) & 0x3) << 5 | + (static_cast(imu_config.gyroscope_odr) & 0x0F)), + // second byte is accel fs + odr + uint8_t((static_cast(imu_config.accelerometer_range) & 0x3) << 5 | + (static_cast(imu_config.accelerometer_odr) & 0x0F))}; + + write_many_to_register(static_cast(Register::GYRO_CONFIG0), data, 2, ec); + if (ec) { + return false; + } + + return true; + } + + /// Set the Accelerometer power mode + /// @param power_mode The power mode + /// @param ec The error code to set if an error occurs + /// @return True if the power mode was set successfully, false otherwise + bool set_accelerometer_power_mode(const AccelerometerPowerMode &power_mode, std::error_code &ec) { + uint8_t bitmask = 0x03; + set_bits_in_register_by_mask(static_cast(Register::PWR_MGMT0), bitmask, + static_cast(power_mode) & bitmask, ec); + return !ec; + } + + /// Set the Gyroscope power mode + /// @param power_mode The power mode + /// @param ec The error code to set if an error occurs + /// @return True if the power mode was set successfully, false otherwise + bool set_gyroscope_power_mode(const GyroscopePowerMode &power_mode, std::error_code &ec) { + uint8_t bitmask = 0x03; + set_bits_in_register_by_mask(static_cast(Register::PWR_MGMT0), bitmask << 2, + (static_cast(power_mode) & bitmask) << 2, ec); + return !ec; + } + + /// Set the Accelerometer filter bandwidth + /// @param bw The filter bandwidth + /// @param ec The error code to set if an error occurs + /// @return True if the filter bandwidth was set successfully, false otherwise + bool set_accelerometer_filter(const SensorFilterBandwidth &bw, std::error_code &ec) { + // ACCEL_FILT_BW is bits 2-0 in ACCEL_CONFIG1 + uint8_t mask = 0x07; + uint8_t data = static_cast(bw) & mask; + set_bits_in_register_by_mask(static_cast(Register::ACCEL_CONFIG1), mask, data, ec); + return !ec; + } + + /// Set the Gyroscope filter bandwidth + /// @param bw The filter bandwidth + /// @param ec The error code to set if an error occurs + /// @return True if the filter bandwidth was set successfully, false otherwise + bool set_gyroscope_filter(const SensorFilterBandwidth &bw, std::error_code &ec) { + // GYRO_FILT_BW is bits 2-0 in GYRO_CONFIG1 + uint8_t mask = 0x07; + uint8_t data = static_cast(bw) & mask; + set_bits_in_register_by_mask(static_cast(Register::GYRO_CONFIG1), mask, data, ec); + return !ec; + } + + /// Initialize the DMP + /// @param ec The error code to set if an error occurs + /// @return True if the DMP was initialized successfully, false otherwise + bool dmp_initialize(std::error_code &ec) { + // DMP INIT EN is bit 2 in APEX_CONFIG0 + set_bits_in_register(static_cast(Register::APEX_CONFIG0), 1 << 2, ec); + return !ec; + } + + /// Set the DMP power save mode + /// @param enable True to enable DMP power save mode, false to disable + /// @param ec The error code to set if an error occurs + /// @return True if the DMP power save mode was set successfully, false otherwise + bool set_dmp_power_save(bool enable, std::error_code &ec) { + // DMP POWER SAVE EN is bit 3 in APEX_CONFIG0 + if (enable) { + set_bits_in_register(static_cast(Register::APEX_CONFIG0), 1 << 3, ec); + } else { + clear_bits_in_register(static_cast(Register::APEX_CONFIG0), 1 << 3, ec); + } + return !ec; + }; + + /// Set the DMP output data rate + /// @param odr The DMP output data rate + /// @param ec The error code to set if an error occurs + /// @return True if the DMP output data rate was set successfully, false + /// otherwise + bool set_dmp_odr(const DmpODR &odr, std::error_code &ec) { + // DMP ODR is bits 1-0 in APEX_CONFIG1 + uint8_t mask = 0x03; + uint8_t data = static_cast(odr) & mask; + set_bits_in_register_by_mask(static_cast(Register::APEX_CONFIG1), mask, data, ec); + return !ec; + } + + /// Read the accelerometer sensitivity + /// @param ec The error code to set if an error occurs + /// @return The accelerometer sensitivity in g/LSB + float get_accelerometer_sensitivity(std::error_code &ec) { + // read the byte from the register + uint8_t data = read_u8_from_register(static_cast(Register::ACCEL_CONFIG0), ec); + if (ec) { + return 0.0f; + } + // get the range + AccelerometerRange range = static_cast((data >> 5) & 0x03); + // convert to sensitivity + return accelerometer_range_to_sensitivty(range); + } + + /// Read the gyroscope sensitivity + /// @param ec The error code to set if an error occurs + /// @return The gyroscope sensitivity in °/s/LSB + float get_gyroscope_sensitivity(std::error_code &ec) { + // read the byte from the register + uint8_t data = read_u8_from_register(static_cast(Register::GYRO_CONFIG0), ec); + if (ec) { + return 0.0f; + } + // get the range + GyroscopeRange range = static_cast((data >> 5) & 0x03); + // convert to sensitivity + return gyroscope_range_to_sensitivty(range); + } + + /// Read the accelerometer data + /// @param ec The error code to set if an error occurs + /// @return The accelerometer data + Value get_accelerometer(std::error_code &ec) { + RawValue raw = get_accelerometer_raw(ec); + if (ec) { + return {0.0f, 0.0f, 0.0f}; + } + float sensitivity = get_accelerometer_sensitivity(ec); + if (ec) { + return {0.0f, 0.0f, 0.0f}; + } + return { + static_cast(raw.x) / sensitivity, + static_cast(raw.y) / sensitivity, + static_cast(raw.z) / sensitivity, + }; + } + + /// Read the gyroscope data + /// @param ec The error code to set if an error occurs + /// @return The gyroscope data + Value get_gyroscope(std::error_code &ec) { + RawValue raw = get_gyroscope_raw(ec); + if (ec) { + return {0.0f, 0.0f, 0.0f}; + } + float sensitivity = get_gyroscope_sensitivity(ec); + if (ec) { + return {0.0f, 0.0f, 0.0f}; + } + return { + static_cast(raw.x) / sensitivity, + static_cast(raw.y) / sensitivity, + static_cast(raw.z) / sensitivity, + }; + } + + /// Read the temperature + /// @param ec The error code to set if an error occurs + /// @return The temperature in °C + float get_temperature(std::error_code &ec) { + uint16_t raw = get_temperature_raw(ec); + if (ec) { + return 0.0f; + } + return static_cast(raw) / 128.0f + 25.0f; // 132.48 + 25 + } + + /// Configure the FIFO buffer + /// @param mode The FIFO mode + /// @param bypassed True if the FIFO is bypassed, false otherwise + /// @param ec The error code to set if an error occurs + /// @return True if the FIFO buffer was configured successfully, false otherwise + bool configure_fifo(const FifoMode &mode, bool bypassed, std::error_code &ec) { + // FIFO_MODE is bit 1, FIFO_BYPASS is bit 0 + uint8_t data = (static_cast(mode) << 1) | (bypassed ? 1 : 0); + write_u8_to_register(static_cast(Register::FIFO_CONFIG1), data, ec); + return !ec; + } + + /// Flush the FIFO buffer + /// @param ec The error code to set if an error occurs + /// @return True if the FIFO buffer was flushed successfully, false otherwise + bool fifo_flush(std::error_code &ec) { + set_bits_in_register(static_cast(Register::SIGNAL_PATH_RESET), FIFO_FLUSH, ec); + return !ec; + } + + /// Get the FIFO count + /// @param ec The error code to set if an error occurs + /// @return The FIFO count. + /// @note The count will be either the number of bytes (if FIFO_COUNT_FORMAT + /// is 0) or the number of records (if FIFO_COUNT_FORMAT is 1). A + /// record is 16 bytes for header + gyro + accel + temp sensor data + + /// time stamp, OR 8 bytes for header + gyro/accel + temp sensor data. + /// @see set_fifo_count_format + uint16_t fifo_count(std::error_code &ec) { + uint8_t data[2]; + read_many_from_register(static_cast(Register::FIFO_COUNTH), data, 2, ec); + if (ec) { + return 0; + } + return (data[0] << 8) | data[1]; + } + + /// Set the FIFO count format to count bytes + /// @param ec The error code to set if an error occurs + /// @return True if the FIFO count format was set successfully, false + /// otherwise + /// @see fifo_count + bool set_fifo_count_bytes(std::error_code &ec) { + uint8_t bitmask = 1 << 6; + clear_bits_in_register(static_cast(Register::INTERFACE_CONFIG0), bitmask, ec); + return !ec; + } + + /// Set the FIFO count format to count records + /// @param ec The error code to set if an error occurs + /// @return True if the FIFO count format was set successfully, false + /// otherwise + /// @see fifo_count + bool set_fifo_count_records(std::error_code &ec) { + uint8_t bitmask = 1 << 6; + set_bits_in_register(static_cast(Register::INTERFACE_CONFIG0), bitmask, ec); + return !ec; + } + + /// Get the FIFO data + /// @param ec The error code to set if an error occurs + /// @return The FIFO data + std::vector fifo_data(std::error_code &ec) { + // get the count + uint16_t count = fifo_count(ec); + if (ec) { + return {}; + } + + // allocate a buffer + std::vector buffer(count); + + // read the data + size_t read_count = read(static_cast(Register::FIFO_DATA), buffer.data(), count, ec); + if (ec) { + return {}; + } + + // check if the number of bytes read is the same as the count + if (read_count != count) { + ec = make_error_code(std::errc::io_error); + return {}; + } + + return buffer; + } + + /// Configure interrupt 1 + /// @param config The interrupt configuration + /// @param ec The error code to set if an error occurs + /// @return True if the interrupt was configured successfully, false otherwise + bool configure_interrupt_1(const InterruptConfig &config, std::error_code &ec) { + // interrupt 1 is bits 0-2 in INT_CONFIG (MODE << 2) | (POLARITY << 1) | DRIVE_MODE + uint8_t mask = 0b111; + uint8_t data = (static_cast(config.mode) << 2) | + (static_cast(config.polarity) << 1) | + static_cast(config.drive_mode); + set_bits_in_register_by_mask(static_cast(Register::INT_CONFIG), mask, data, ec); + return !ec; + } + + /// Configure interrupt 2 + /// @param config The interrupt configuration + /// @param ec The error code to set if an error occurs + /// @return True if the interrupt was configured successfully, false otherwise + bool configure_interrupt_2(const InterruptConfig &config, std::error_code &ec) { + // interrupt 2 is bits 3-5 in INT_CONFIG (MODE << 5) | (POLARITY << 4) | (DRIVE_MODE << 3) + uint8_t mask = 0b111 << 3; + uint8_t data = (static_cast(config.mode) << 5) | + (static_cast(config.polarity) << 4) | + (static_cast(config.drive_mode) << 3); + set_bits_in_register_by_mask(static_cast(Register::INT_CONFIG), mask, data, ec); + return !ec; + } + + /// Read whether the data is ready + /// @param ec The error code to set if an error occurs + /// @return True if the data is ready, false otherwise + /// @note This will clear the data ready interrupt bit, which is + /// automatically set to 1 when a Data Ready interrupt is generated. + bool is_data_ready(std::error_code &ec) { + // clearing the bit just involves reading the register + uint8_t data_ready = + read_u8_from_register(static_cast(Register::INT_STATUS_DATA_READY), ec); + return !ec && (data_ready & 0x01); + } + +protected: + static constexpr float RAD_TO_DEG = 57.27272727f; ///< Radians to degrees + static constexpr float DEG_TO_RAD = 0.01745329252f; ///< Degrees to radians + + static constexpr uint8_t ICM42607_ID = 0x60; ///< ICM42607 ID + static constexpr uint8_t ICM42670_ID = 0x67; ///< ICM42670 ID + + static constexpr float GYRO_FS_2000_SENS = 16.4f; ///< Gyroscope sensitivity for ±2000°/s + static constexpr float GYRO_FS_1000_SENS = 32.8f; ///< Gyroscope sensitivity for ±1000°/s + static constexpr float GYRO_FS_500_SENS = 65.5f; ///< Gyroscope sensitivity for ±500°/s + static constexpr float GYRO_FS_250_SENS = 131.0f; ///< Gyroscope sensitivity for ±250°/s + + static constexpr float ACCEL_FS_16G_SENS = 2048.0f; ///< Accelerometer sensitivity for ±16g + static constexpr float ACCEL_FS_8G_SENS = 4096.0f; ///< Accelerometer sensitivity for ±8g + static constexpr float ACCEL_FS_4G_SENS = 8192.0f; ///< Accelerometer sensitivity for ±4g + static constexpr float ACCEL_FS_2G_SENS = 16384.0f; ///< Accelerometer sensitivity for ±2g + + static constexpr uint8_t FIFO_FLUSH = (1 << 2); ///< FIFO flush bit, in register SIGNAL_PATH_RESET + + /// Register addresses + enum class Register : uint8_t { + /// USER BANK 0 + + MCLK_READY_STATUS = 0x00, ///< MCLK ready status register + DEVICE_CONFIG = 0x01, ///< Device configuration register + SIGNAL_PATH_RESET = 0x02, ///< Signal path reset register + + DRIVE_CONFIG_1 = 0x03, ///< Drive configuration 1 register + DRIVE_CONFIG_2 = 0x04, ///< Drive configuration 2 register + DRIVE_CONFIG_3 = 0x05, ///< Drive configuration 3 register + + INT_CONFIG = 0x06, ///< Interrupt configuration register + + TEMP_DATA = 0x09, ///< Temperature data register + ACCEL_DATA = 0x0B, ///< Accelerometer data register + GYRO_DATA = 0x11, ///< Gyroscope data register + + APEX_DATA4 = 0x1D, ///< APEX data 4 register, contains FF_DUR_L (freefall duration lower byte) + APEX_DATA5 = 0x1E, ///< APEX data 5 register, contains FF_DUR_H (freefall duration higher byte) + + PWR_MGMT0 = 0x1F, ///< Power management register + + GYRO_CONFIG0 = 0x20, ///< Gyroscope configuration register + ACCEL_CONFIG0 = 0x21, ///< Accelerometer configuration register + TEMP_CONFIG = 0x22, ///< Temperature configuration register. Stores the configuration for the + ///< temperature DLPF BW. + GYRO_CONFIG1 = 0x23, ///< Gyroscope configuration 1 register. Stores the configuration for the + ///< gyroscope LPF BW. + ACCEL_CONFIG1 = 0x24, ///< Accelerometer configuration 1 register. Stores the configuration for + ///< the accelerometer LPF BW. + + APEX_CONFIG0 = 0x25, ///< APEX configuration 0 register + APEX_CONFIG1 = 0x26, ///< APEX configuration 1 register + + WOM_CONFIG0 = 0x27, ///< Wake-on-motion (WOM) configuration 0 register + + FIFO_CONFIG1 = 0x28, ///< FIFO configuration 1 register + FIFO_CONFIG2 = 0x29, ///< FIFO configuration 2 register + FIFO_CONFIG3 = 0x2A, ///< FIFO configuration 3 register + + INT_SOURCE0 = 0x2B, ///< Interrupt source 0 register + INT_SOURCE1 = 0x2C, ///< Interrupt source 1 register + // Datasheet doesn't have INT_SOURCE2??? + INT_SOURCE3 = 0x2D, ///< Interrupt source 3 register + INT_SOURCE4 = 0x2E, ///< Interrupt source 4 register + + FIFO_LOST_PKT0 = + 0x2F, ///< FIFO lost packet 0 register. Low byte for number of packets lost in the FIFO + FIFO_LOST_PKT1 = + 0x30, ///< FIFO lost packet 1 register. High byte for number of packets lost in the FIFO + + APEX_DATA0 = 0x31, ///< APEX data 0 register. Contains pedometer output (lower byte step count) + APEX_DATA1 = 0x32, ///< APEX data 1 register. Contains pedometer output (higher byte step count) + APEX_DATA2 = 0x33, ///< APEX data 2 register. Pedometer output - walk/run cadency in number of + ///< samples formatted as u6.2. e.g. At 50 Hz ODR and 2 Hz walk frequency, + ///< the cadency is 25 samples and register will output 100. + APEX_DATA3 = 0x34, ///< APEX data 3 register. Contains DMP_IDLE bit and ACTIVITY_CLASS bits (00: + ///< unk, 01: walk, 10: run, 11: reserved) + + INTERFACE_CONFIG0 = 0x35, ///< Interface configuration 0 register + INTERFACE_CONFIG1 = 0x36, ///< Interface configuration 1 register + + INT_STATUS_DATA_READY = 0x39, ///< Interrupt status data ready register + INT_STATUS1 = 0x3A, ///< Interrupt status 1 register + INT_STATUS2 = 0x3B, ///< Interrupt status 2 register + INT_STATUS3 = 0x3C, ///< Interrupt status 3 register + + FIFO_COUNTH = 0x3D, ///< FIFO count high register + FIFO_COUNTL = 0x3E, ///< FIFO count low register + + FIFO_DATA = 0x3F, ///< FIFO data register + + WHO_AM_I = 0x75, ///< Who am I register + + BLK_SEL_W = 0x79, ///< Block select write register + MADDR_W = 0x7A, ///< Memory address write register + M_WR_DATA = 0x7B, ///< Memory write data register + + BLK_SEL_R = 0x7C, ///< Block select read register + MADDR_R = 0x7D, ///< Memory address read register + M_RD_DATA = 0x7E, ///< Memory read data register + + /// USER BANK MREG1 + + // TODO: fill out from datasheet pp. 43-44 + + /// USER BANK MREG2 + + OTP_CTRL7 = 0x06, ///< OTP control 7 register + + /// USER BANK MREG3 + + XA_ST_DATA = 0x00, ///< X-axis accelerometer self-test data register + YA_ST_DATA = 0x01, ///< Y-axis accelerometer self-test data register + ZA_ST_DATA = 0x02, ///< Z-axis accelerometer self-test data register + XG_ST_DATA = 0x03, ///< X-axis gyroscope self-test data register + YG_ST_DATA = 0x04, ///< Y-axis gyroscope self-test data register + ZG_ST_DATA = 0x05, ///< Z-axis gyroscope self-test data register + }; + + /// @brief Structure for the ICM42607 FIFO header + struct FifoHeader { + uint8_t odr_gyro : 1; ///< 1: ODfor gyro is different fro this packet comapred to previous gyro + ///< packet + uint8_t odr_accel : 1; ///< 1: ODfor accel is different fro this packet comapred to previous + ///< accel packet + uint8_t timestamp_fsync : 2; ///< 0b00: no timestamp or fsync data, 0b01: reserved, 0b10: ODR + ///< timestamp, 0b11: FSYNC timestamp + uint8_t extended : 1; ///< 1: packet contains 20-bit data for gyro and/or accel + uint8_t has_gyro : 1; ///< 1: Packet is sized so that it contains gyroscope data + uint8_t has_accel : 1; ///< 1: Packet is sized so that it contains accelerometer data + uint8_t empty : 1; ///< 1: Packet is empty, 0: packet contains sensor data + } __attribute__((packed)); + + /// @brief Struct for the FIFO Packet 1 data + struct FifoPacket1 { + FifoHeader header; ///< FIFO header + std::array accel; ///< Accelerometer data (x,y,z) + uint8_t temperature; ///< Temperature data + }; + + /// @brief Struct for the FIFO Packet 2 data + struct FifoPacket2 { + FifoHeader header; ///< FIFO header + std::array gyro; ///< Gyroscope data (x,y,z) + uint8_t temperature; ///< Temperature data + }; + + /// @brief Struct for the FIFO Packet 3 data + struct FifoPacket3 { + FifoHeader header; ///< FIFO header + std::array accel; ///< Accelerometer data (x,y,z) + std::array gyro; ///< Gyroscope data (x,y,z) + uint8_t temperature; ///< Temperature data + uint16_t timestamp_us; ///< Timestamp in microseconds + }; + + /// @brief Struct for the FIFO Packet 4 data + struct FifoPacket4 { + FifoHeader header; ///< FIFO header + std::array accel; ///< Accelerometer data (x,y,z) bits [19:4] + std::array gyro; ///< Gyroscope data (x,y,z) bits [19:4] + uint16_t temperature; ///< Temperature data + uint16_t timestamp_us; ///< Timestamp in microseconds + uint8_t + x_extension; ///< X-axis extension data (accelx [3:0] high nibble + gyrox [3:0] low nibble) + uint8_t + y_extension; ///< Y-axis extension data (accely [3:0] high nibble + gyroy [3:0] low nibble) + uint8_t + z_extension; ///< Z-axis extension data (accelz [3:0] high nibble + gyroz [3:0] low nibble) + }; + + static float accelerometer_range_to_sensitivty(const AccelerometerRange &range) { + switch (range) { + case AccelerometerRange::RANGE_16G: + return ACCEL_FS_16G_SENS; + case AccelerometerRange::RANGE_8G: + return ACCEL_FS_8G_SENS; + case AccelerometerRange::RANGE_4G: + return ACCEL_FS_4G_SENS; + case AccelerometerRange::RANGE_2G: + return ACCEL_FS_2G_SENS; + default: + return 0.0f; + } + } + + static float gyroscope_range_to_sensitivty(const GyroscopeRange &range) { + switch (range) { + case GyroscopeRange::RANGE_2000DPS: + return GYRO_FS_2000_SENS; + case GyroscopeRange::RANGE_1000DPS: + return GYRO_FS_1000_SENS; + case GyroscopeRange::RANGE_500DPS: + return GYRO_FS_500_SENS; + case GyroscopeRange::RANGE_250DPS: + return GYRO_FS_250_SENS; + default: + return 0.0f; + } + } + + uint16_t get_temperature_raw(std::error_code &ec) { + return read_u16_from_register(static_cast(Register::TEMP_DATA), ec); + } + + RawValue get_accelerometer_raw(std::error_code &ec) { return get_raw(Register::ACCEL_DATA, ec); } + + RawValue get_gyroscope_raw(std::error_code &ec) { return get_raw(Register::GYRO_DATA, ec); } + + RawValue get_raw(Register reg, std::error_code &ec) { + uint8_t data[6]; + read_many_from_register(static_cast(reg), data, 6, ec); + if (ec) { + return {0, 0, 0}; + } + return { + static_cast((data[0] << 8) | data[1]), + static_cast((data[2] << 8) | data[3]), + static_cast((data[4] << 8) | data[5]), + }; + } + + ImuConfig imu_config_{}; ///< IMU configuration +}; // class Icm42607 +} // namespace espp diff --git a/components/icm42607/include/icm42607_detail.hpp b/components/icm42607/include/icm42607_detail.hpp new file mode 100644 index 000000000..1a6602347 --- /dev/null +++ b/components/icm42607/include/icm42607_detail.hpp @@ -0,0 +1,336 @@ +#pragma once + +#include + +namespace espp { +/// @brief Namespace for the ICM42607 6-axis motion sensor +namespace icm42607 { +/// @brief Enum class for the interface type of the ICM42607 +enum class Interface : uint8_t { + I2C = 0, ///< Inter-Integrated Circuit (I2C) + SSI = 1, ///< Synchronous Serial Interface (SSI), which can be SPI or SSI +}; + +/// @brief Enum class for FIFO configuration +enum class FifoMode : uint8_t { + STREAM = 0, ///< Stream mode + STOP_ON_FULL = 1, ///< Stop on full mode +}; + +/// Accelerometer range +enum class AccelerometerRange : uint8_t { + RANGE_16G = 0, ///< ±16g + RANGE_8G = 1, ///< ±8g + RANGE_4G = 2, ///< ±4g + RANGE_2G = 3, ///< ±2g +}; + +/// Accelerometer power mode +enum class AccelerometerPowerMode : uint8_t { + OFF = 0, ///< Off + ON = 1, ///< On + LOW_POWER = 2, ///< Low power + LOW_NOISE = 3, ///< Low noise +}; + +/// Accelerometer output data rate +enum class AccelerometerODR : uint8_t { + ODR_1600_HZ = 5, ///< 1600 Hz + ODR_800_HZ = 6, ///< 800 Hz + ODR_400_HZ = 7, ///< 400 Hz + ODR_200_HZ = 8, ///< 200 Hz + ODR_100_HZ = 9, ///< 100 Hz + ODR_50_HZ = 10, ///< 50 Hz + ODR_25_HZ = 11, ///< 25 Hz + ODR_12_5_HZ = 12, ///< 12.5 Hz + ODR_6_25_HZ = 13, ///< 6.25 Hz + ODR_3_125_HZ = 14, ///< 3.125 Hz + ODR_1_5625_HZ = 15, ///< 1.5625 Hz +}; + +/// Gyroscope range +enum class GyroscopeRange : uint8_t { + RANGE_2000DPS = 0, ///< ±2000°/s + RANGE_1000DPS = 1, ///< ±1000°/s + RANGE_500DPS = 2, ///< ±500°/s + RANGE_250DPS = 3, ///< ±250°/s +}; + +/// Gyroscope power mode +enum class GyroscopePowerMode : uint8_t { + OFF = 0, ///< Off + STANDBY = 1, ///< Standby + LOW_NOISE = 3, ///< Low noise +}; + +/// Gyroscope output data rate +enum class GyroscopeODR : uint8_t { + ODR_1600_HZ = 5, ///< 1600 Hz + ODR_800_HZ = 6, ///< 800 Hz + ODR_400_HZ = 7, ///< 400 Hz + ODR_200_HZ = 8, ///< 200 Hz + ODR_100_HZ = 9, ///< 100 Hz + ODR_50_HZ = 10, ///< 50 Hz + ODR_25_HZ = 11, ///< 25 Hz + ODR_12_5_HZ = 12, ///< 12.5 Hz +}; + +/// Digital Motion Processor (DMP) output data rate +enum class DmpODR : uint8_t { + ODR_25_HZ = 0, ///< 25 Hz + ODR_400_HZ = 1, ///< 200 Hz + ODR_50_HZ = 2, ///< 50 Hz + ODR_100_HZ = 3, ///< 100 Hz +}; + +/// Temperature DLPF Bandwidth +enum class TemperatureFilterBandwidth : uint8_t { + FILTER_OFF = 0, ///< Filter off + BW_180_HZ = 1, ///< 180 Hz + BW_72_HZ = 2, ///< 72 Hz + BW_34_HZ = 3, ///< 34 Hz + BW_16_HZ = 4, ///< 16 Hz + BW_8_HZ = 5, ///< 8 Hz + BW_4_HZ = 6, ///< 4 Hz + // NOTE: datasheet has both 0b111 and 0b110 matching to 4 Hz +}; + +/// Sensor DLPF Bandwidth for both accelerometer and gyroscope +enum class SensorFilterBandwidth : uint8_t { + FILTER_OFF = 0, ///< Filter off + BW_180_HZ = 1, ///< 180 Hz + BW_121_HZ = 2, ///< 121 Hz + BW_73_HZ = 3, ///< 73 Hz + BW_53_HZ = 4, ///< 53 Hz + BW_34_HZ = 5, ///< 34 Hz + BW_25_HZ = 6, ///< 25 Hz + BW_16_HZ = 7, ///< 16 Hz +}; + +/// IMU Configuration +struct ImuConfig { + AccelerometerRange accelerometer_range = AccelerometerRange::RANGE_16G; ///< Accelerometer range + AccelerometerODR accelerometer_odr = + AccelerometerODR::ODR_100_HZ; ///< Accelerometer output data rate + GyroscopeRange gyroscope_range = GyroscopeRange::RANGE_2000DPS; ///< Gyroscope range + GyroscopeODR gyroscope_odr = GyroscopeODR::ODR_100_HZ; ///< Gyroscope output data rate +}; + +/// Raw IMU data +struct RawValue { + int16_t x; ///< Raw X-axis value + int16_t y; ///< Raw Y-axis value + int16_t z; ///< Raw Z-axis value +}; + +/// IMU data +struct Value { + float x; ///< X-axis value + float y; ///< Y-axis value + float z; ///< Z-axis value +}; + +/// Complimentary angle +struct ComplimentaryAngle { + float roll; ///< Roll angle + float pitch; ///< Pitch angle +}; + +/// @brief Enum class for the ICM42607 interrupt configuration +enum class InterruptDriveMode { + OPEN_DRAIN = 0, ///< Open drain + PUSH_PULL = 1, ///< Push-pull +}; + +/// @brief Enum class for the ICM42607 interrupt configuration +enum class InterruptPolarity { + ACTIVE_LOW = 0, ///< Active low + ACTIVE_HIGH = 1, ///< Active high +}; + +/// @brief Enum class for the ICM42607 interrupt configuration +enum class InterruptMode { + PULSED = 0, ///< Pulsed + LATCHED = 1, ///< Latched +}; + +/// @brief Struct for the ICM42607 interrupt configuration +struct InterruptConfig { + InterruptDriveMode drive_mode; ///< Drive mode + InterruptPolarity polarity; ///< Polarity + InterruptMode mode; ///< Mode +}; +} // namespace icm42607 +} // namespace espp + +#include "format.hpp" + +// for libfmt printing of relevant imu types and structs +template <> struct fmt::formatter { + constexpr auto parse(format_parse_context &ctx) const { return ctx.begin(); } + template + auto format(espp::icm42607::AccelerometerRange range, FormatContext &ctx) const { + switch (range) { + case espp::icm42607::AccelerometerRange::RANGE_16G: + return format_to(ctx.out(), "±16g"); + case espp::icm42607::AccelerometerRange::RANGE_8G: + return format_to(ctx.out(), "±8g"); + case espp::icm42607::AccelerometerRange::RANGE_4G: + return format_to(ctx.out(), "±4g"); + case espp::icm42607::AccelerometerRange::RANGE_2G: + return format_to(ctx.out(), "±2g"); + default: + return format_to(ctx.out(), "Unknown"); + } + } +}; + +template <> struct fmt::formatter { + constexpr auto parse(format_parse_context &ctx) const { return ctx.begin(); } + template + auto format(espp::icm42607::AccelerometerPowerMode power_mode, FormatContext &ctx) const { + switch (power_mode) { + case espp::icm42607::AccelerometerPowerMode::OFF: + return format_to(ctx.out(), "Off"); + case espp::icm42607::AccelerometerPowerMode::ON: + return format_to(ctx.out(), "On"); + case espp::icm42607::AccelerometerPowerMode::LOW_POWER: + return format_to(ctx.out(), "Low power"); + case espp::icm42607::AccelerometerPowerMode::LOW_NOISE: + return format_to(ctx.out(), "Low noise"); + default: + return format_to(ctx.out(), "Unknown"); + } + } +}; + +template <> struct fmt::formatter { + constexpr auto parse(format_parse_context &ctx) const { return ctx.begin(); } + template + auto format(espp::icm42607::AccelerometerODR odr, FormatContext &ctx) const { + switch (odr) { + case espp::icm42607::AccelerometerODR::ODR_1600_HZ: + return format_to(ctx.out(), "1600 Hz"); + case espp::icm42607::AccelerometerODR::ODR_800_HZ: + return format_to(ctx.out(), "800 Hz"); + case espp::icm42607::AccelerometerODR::ODR_400_HZ: + return format_to(ctx.out(), "400 Hz"); + case espp::icm42607::AccelerometerODR::ODR_200_HZ: + return format_to(ctx.out(), "200 Hz"); + case espp::icm42607::AccelerometerODR::ODR_100_HZ: + return format_to(ctx.out(), "100 Hz"); + case espp::icm42607::AccelerometerODR::ODR_50_HZ: + return format_to(ctx.out(), "50 Hz"); + case espp::icm42607::AccelerometerODR::ODR_25_HZ: + return format_to(ctx.out(), "25 Hz"); + case espp::icm42607::AccelerometerODR::ODR_12_5_HZ: + return format_to(ctx.out(), "12.5 Hz"); + case espp::icm42607::AccelerometerODR::ODR_6_25_HZ: + return format_to(ctx.out(), "6.25 Hz"); + case espp::icm42607::AccelerometerODR::ODR_3_125_HZ: + return format_to(ctx.out(), "3.125 Hz"); + case espp::icm42607::AccelerometerODR::ODR_1_5625_HZ: + return format_to(ctx.out(), "1.5625 Hz"); + default: + return format_to(ctx.out(), "Unknown"); + } + } +}; + +template <> struct fmt::formatter { + constexpr auto parse(format_parse_context &ctx) const { return ctx.begin(); } + template + auto format(espp::icm42607::GyroscopeRange range, FormatContext &ctx) const { + switch (range) { + case espp::icm42607::GyroscopeRange::RANGE_2000DPS: + return format_to(ctx.out(), "±2000°/s"); + case espp::icm42607::GyroscopeRange::RANGE_1000DPS: + return format_to(ctx.out(), "±1000°/s"); + case espp::icm42607::GyroscopeRange::RANGE_500DPS: + return format_to(ctx.out(), "±500°/s"); + case espp::icm42607::GyroscopeRange::RANGE_250DPS: + return format_to(ctx.out(), "±250°/s"); + default: + return format_to(ctx.out(), "Unknown"); + } + } +}; + +template <> struct fmt::formatter { + constexpr auto parse(format_parse_context &ctx) const { return ctx.begin(); } + template + auto format(espp::icm42607::GyroscopePowerMode power_mode, FormatContext &ctx) const { + switch (power_mode) { + case espp::icm42607::GyroscopePowerMode::OFF: + return format_to(ctx.out(), "Off"); + case espp::icm42607::GyroscopePowerMode::STANDBY: + return format_to(ctx.out(), "Standby"); + case espp::icm42607::GyroscopePowerMode::LOW_NOISE: + return format_to(ctx.out(), "Low noise"); + default: + return format_to(ctx.out(), "Unknown"); + } + } +}; + +template <> struct fmt::formatter { + constexpr auto parse(format_parse_context &ctx) const { return ctx.begin(); } + template + auto format(espp::icm42607::GyroscopeODR odr, FormatContext &ctx) const { + switch (odr) { + case espp::icm42607::GyroscopeODR::ODR_1600_HZ: + return format_to(ctx.out(), "1600 Hz"); + case espp::icm42607::GyroscopeODR::ODR_800_HZ: + return format_to(ctx.out(), "800 Hz"); + case espp::icm42607::GyroscopeODR::ODR_400_HZ: + return format_to(ctx.out(), "400 Hz"); + case espp::icm42607::GyroscopeODR::ODR_200_HZ: + return format_to(ctx.out(), "200 Hz"); + case espp::icm42607::GyroscopeODR::ODR_100_HZ: + return format_to(ctx.out(), "100 Hz"); + case espp::icm42607::GyroscopeODR::ODR_50_HZ: + return format_to(ctx.out(), "50 Hz"); + case espp::icm42607::GyroscopeODR::ODR_25_HZ: + return format_to(ctx.out(), "25 Hz"); + case espp::icm42607::GyroscopeODR::ODR_12_5_HZ: + return format_to(ctx.out(), "12.5 Hz"); + default: + return format_to(ctx.out(), "Unknown"); + } + } +}; + +template <> struct fmt::formatter { + constexpr auto parse(format_parse_context &ctx) const { return ctx.begin(); } + template + auto format(const espp::icm42607::ImuConfig &config, FormatContext &ctx) const { + return format_to(ctx.out(), + "Accelerometer: {{ range: {}, odr: {} }}, Gyroscope: {{ range: {}, odr: {} }}", + config.accelerometer_range, config.accelerometer_odr, config.gyroscope_range, + config.gyroscope_odr); + } +}; + +template <> struct fmt::formatter { + constexpr auto parse(format_parse_context &ctx) const { return ctx.begin(); } + template + auto format(const espp::icm42607::RawValue &raw, FormatContext &ctx) const { + return format_to(ctx.out(), "{{ x: {}, y: {}, z: {} }}", raw.x, raw.y, raw.z); + } +}; + +template <> struct fmt::formatter { + constexpr auto parse(format_parse_context &ctx) const { return ctx.begin(); } + template + auto format(const espp::icm42607::Value &value, FormatContext &ctx) const { + return format_to(ctx.out(), "{{ x: {:.2f}, y: {:.2f}, z: {:.2f} }}", value.x, value.y, value.z); + } +}; + +template <> struct fmt::formatter { + constexpr auto parse(format_parse_context &ctx) const { return ctx.begin(); } + template + auto format(const espp::icm42607::ComplimentaryAngle &angle, FormatContext &ctx) const { + return format_to(ctx.out(), "{{ roll: {:.2f}, pitch: {:.2f} }}", angle.roll, angle.pitch); + } +}; diff --git a/components/math/example/main/math_example.cpp b/components/math/example/main/math_example.cpp index 26fe19417..bea8b67d3 100644 --- a/components/math/example/main/math_example.cpp +++ b/components/math/example/main/math_example.cpp @@ -47,10 +47,10 @@ extern "C" void app_main(void) { //! [fast_ln example] } { - //! [fast_sqrt example] + //! [fast_inv_sqrt example] float x = 3.0f; auto slow = sqrt(x); - auto fast = espp::fast_sqrt(x); + auto fast = 1.0f / espp::fast_inv_sqrt(x); auto diff = std::abs(slow - fast); fmt::print("sqrt({}) = {} (slow), {} (fast), diff = {}\n", x, slow, fast, diff); //! [fast_sqrt example] diff --git a/components/math/include/fast_math.hpp b/components/math/include/fast_math.hpp index d6e640d1e..8b221687f 100644 --- a/components/math/include/fast_math.hpp +++ b/components/math/include/fast_math.hpp @@ -1,6 +1,8 @@ #pragma once +#include #include +#include #include #include #include @@ -22,27 +24,15 @@ namespace espp { [[maybe_unused]] static float cube(float f) { return f * f * f; } /** - * @brief Fast square root approximation. + * @brief Fast inverse square root approximation. * @note Using https://reprap.org/forum/read.php?147,219210 and * https://en.wikipedia.org/wiki/Fast_inverse_square_root - * @param value Value to take the square root of. - * @return Approximation of the square root of value. + * @param value Value to take the inverse square root of. + * @return Approximation of the inverse square root of value. */ -[[maybe_unused]] static float fast_sqrt(float value) { - uint32_t i{0}; - float y{0}; - // float x; - // const float f = 1.5F; // better precision - - // x = number * 0.5F; - y = value; - memcpy(&i, &y, sizeof(i)); - // i = * reinterpret_cast(&y); - i = 0x5f375a86 - (i >> 1); - // y = * reinterpret_cast(&i); - memcpy(&y, &i, sizeof(y)); - // y = y * ( f - ( x * y * y ) ); // better precision - return value * y; +[[maybe_unused]] static constexpr float fast_inv_sqrt(float value) noexcept { + const auto y = std::bit_cast(0x5f3759df - (std::bit_cast(value) >> 1)); + return y * (1.5f - (0.5f * value * y * y)); } /** diff --git a/doc/Doxyfile b/doc/Doxyfile index a6cf759e1..cc2204712 100644 --- a/doc/Doxyfile +++ b/doc/Doxyfile @@ -52,6 +52,7 @@ EXAMPLE_PATH += $(PROJECT_PATH)/components/gt911/example/main/gt911_example.cpp EXAMPLE_PATH += $(PROJECT_PATH)/components/hid-rp/example/main/hid_rp_example.cpp EXAMPLE_PATH += $(PROJECT_PATH)/components/hid_service/example/main/hid_service_example.cpp EXAMPLE_PATH += $(PROJECT_PATH)/components/i2c/example/main/i2c_example.cpp +EXAMPLE_PATH += $(PROJECT_PATH)/components/icm42607/example/main/icm42607_example.cpp EXAMPLE_PATH += $(PROJECT_PATH)/components/interrupt/example/main/interrupt_example.cpp EXAMPLE_PATH += $(PROJECT_PATH)/components/joystick/example/main/joystick_example.cpp EXAMPLE_PATH += $(PROJECT_PATH)/components/kts1622/example/main/kts1622_example.cpp @@ -144,7 +145,10 @@ INPUT += $(PROJECT_PATH)/components/event_manager/include/event_manager.hpp INPUT += $(PROJECT_PATH)/components/file_system/include/file_system.hpp INPUT += $(PROJECT_PATH)/components/filters/include/biquad_filter.hpp INPUT += $(PROJECT_PATH)/components/filters/include/butterworth_filter.hpp +INPUT += $(PROJECT_PATH)/components/filters/include/complementary_filter.hpp +INPUT += $(PROJECT_PATH)/components/filters/include/kalman_filter.hpp INPUT += $(PROJECT_PATH)/components/filters/include/lowpass_filter.hpp +INPUT += $(PROJECT_PATH)/components/filters/include/madgwick_filter.hpp INPUT += $(PROJECT_PATH)/components/filters/include/simple_lowpass_filter.hpp INPUT += $(PROJECT_PATH)/components/filters/include/sos_filter.hpp INPUT += $(PROJECT_PATH)/components/filters/include/transfer_function.hpp @@ -162,6 +166,8 @@ INPUT += $(PROJECT_PATH)/components/hid-rp/include/hid-rp-xbox.hpp INPUT += $(PROJECT_PATH)/components/hid_service/include/hid_service.hpp INPUT += $(PROJECT_PATH)/components/i2c/include/i2c.hpp INPUT += $(PROJECT_PATH)/components/i2c/include/i2c_menu.hpp +INPUT += $(PROJECT_PATH)/components/icm42607/include/icm42607.hpp +INPUT += $(PROJECT_PATH)/components/icm42607/include/icm42607_detail.hpp INPUT += $(PROJECT_PATH)/components/interrupt/include/interrupt.hpp INPUT += $(PROJECT_PATH)/components/input_drivers/include/encoder_input.hpp INPUT += $(PROJECT_PATH)/components/input_drivers/include/keypad_input.hpp diff --git a/doc/en/filters/complementary.rst b/doc/en/filters/complementary.rst new file mode 100644 index 000000000..2b557edf2 --- /dev/null +++ b/doc/en/filters/complementary.rst @@ -0,0 +1,15 @@ +Complementary Filter +******************** + +The `ComplementaryFilter` provides a simple implementation of a filter +specifically designed to combine the outputs of a gyroscope and an accelerometer +to produce a more accurate estimate of the orientation of an object. This filter +is provided for completeness and simplicity, but the `KalmanFilter` or +`MadgwickFilter` are generally preferred for this purpose. + +.. ---------------------------- API Reference ---------------------------------- + +API Reference +------------- + +.. include-build-file:: inc/complementary_filter.inc diff --git a/doc/en/filters/index.rst b/doc/en/filters/index.rst index 4a8260999..8101cb832 100644 --- a/doc/en/filters/index.rst +++ b/doc/en/filters/index.rst @@ -7,7 +7,10 @@ Filter APIs filters_example biquad butterworth + complementary + kalman lowpass + madgwick simple_lowpass sos transfer_function diff --git a/doc/en/filters/kalman.rst b/doc/en/filters/kalman.rst new file mode 100644 index 000000000..336ac2840 --- /dev/null +++ b/doc/en/filters/kalman.rst @@ -0,0 +1,19 @@ +Kalman Filter +************* + +The `KalmanFilter` class implements a Kalman filter for linear systems. The +filter can be used to estimate the state of a linear system given noisy +measurements. The filter can be configured for an arbitrary number of states +and measurements. You can also specify the process noise and measurement noise +covariances. + +To use the filter, you must first create an instance of the `KalmanFilter` +class, then call the `predict` and `update` methods to estimate the state of +the system. To get the current state estimate, call the `get_state` method. + +.. ---------------------------- API Reference ---------------------------------- + +API Reference +------------- + +.. include-build-file:: inc/kalman_filter.inc diff --git a/doc/en/filters/madgwick.rst b/doc/en/filters/madgwick.rst new file mode 100644 index 000000000..f97ed71c6 --- /dev/null +++ b/doc/en/filters/madgwick.rst @@ -0,0 +1,15 @@ +Madgwick Filter +*************** + +The `MadgwickFilter` implements the Madgwick algorithm for orientation +estimation using an IMU. The algorithm is based on the paper `An efficient +orientation filter for inertial and inertial/magnetic sensor arrays`_ by +Sebastian Madgwick. It supports state / orientation estimation for both 6-axis +IMUs as well as for 9-axis IMUs. + +.. ---------------------------- API Reference ---------------------------------- + +API Reference +------------- + +.. include-build-file:: inc/madgwick_filter.inc diff --git a/doc/en/imu/icm42607.rst b/doc/en/imu/icm42607.rst new file mode 100644 index 000000000..82061d586 --- /dev/null +++ b/doc/en/imu/icm42607.rst @@ -0,0 +1,19 @@ +ICM42607 6-Axis IMU +******************* + +The `Icm42607` component provides a driver for the ICM42607 and ICM42670 6-Axis +Inertial Measurement Units (IMUs). + +.. ------------------------------- Example ------------------------------------- + +.. toctree:: + + icm42607_example + +.. ---------------------------- API Reference ---------------------------------- + +API Reference +------------- + +.. include-build-file:: inc/icm42607.inc +.. include-build-file:: inc/icm42607_detail.inc diff --git a/doc/en/imu/icm42607_example.md b/doc/en/imu/icm42607_example.md new file mode 100644 index 000000000..5068ed225 --- /dev/null +++ b/doc/en/imu/icm42607_example.md @@ -0,0 +1,2 @@ +```{include} ../../../components/icm42607/example/README.md +``` diff --git a/doc/en/imu/index.rst b/doc/en/imu/index.rst new file mode 100644 index 000000000..e11b831b5 --- /dev/null +++ b/doc/en/imu/index.rst @@ -0,0 +1,9 @@ +IMU APIs +******** + +.. toctree:: + :maxdepth: 1 + + icm42607 + +Code examples for the IMU APIs are provided in the respective component folders. diff --git a/doc/en/index.rst b/doc/en/index.rst index a33378ebf..223459d36 100644 --- a/doc/en/index.rst +++ b/doc/en/index.rst @@ -32,6 +32,7 @@ This is the documentation for esp-idf c++ components, ESPP (`espp (espp::sgn), py::arg("x"), "*\n * @brief Get the sign of a number (+1, 0, or -1)\n * @param x Value to get the sign "