ICM20948 9-Axis IMU
The Icm20948 component provides a driver for the ICM20948 9-Axis Inertial Measurement Unit (IMU).
API Reference
Header File
Classes
-
template<icm20948::Interface Interface = icm20948::Interface::I2C>
class Icm20948 : public espp::BasePeripheral<uint8_t, icm20948::Interface::I2C == icm20948::Interface::I2C> Class for the ICM20948 9-axis motion sensor.
The ICM-20948 IMU is a 9-axis motion sensor that combines a 3-axis gyroscope, 3-axis accelerometer, and 3-axis magnetometer. The ICM-20948 is a 16-bit sensor that can measure acceleration up to ±16g, angular velocity up to ±2000°/s, and magnetic field up to ±4900 µT. The magnetic field sensor used is the AK09916C.
Stats:
Accelerometer range: ±2g, ±4g, ±8g, ±16g
Accelerometer sensitivity: 16384, 8192, 4096, 2048 LSB/g
Accelerometer output data rate: 4.5 Hz - 4.5 kHz
Gyroscope range: ±250°/s, ±500°/s, ±1000°/s, ±2000°/s
Gyroscope sensitivity: 131, 65.5, 32.8, 16.4 LSB/(°/s)
Gyroscope output data rate: 4.4 - 9 kHz
Magnetometer range: ±4900 µT
Magnetometer sensitivity: 0.15 µT/LSB
Magnetometer output data rate: 10 Hz - 100 Hz
Using the ADA and ACL lines, the ICM-20948 can be configured to control / communicate with auxiliary I2C sensors.
The ICM-20948 has a FIFO buffer that can store up to 4 kB of data. The FIFO buffer can be configured to store gyroscope, accelerometer, and temperature data. The FIFO buffer can be used to store data for batch processing or to reduce the number of interrupts generated by the ICM-20948.
The ICM-20948 has a Digital Motion Processor (DMP) that can be used to offload sensor fusion calculations from the host processor. The DMP can be used to calculate quaternion, rotation matrix, and Euler angles. The DMP can also be used to detect gestures, such as tap, shake, and orientation.
The ICM-20948 has a wake-on-motion (WOM) feature that can be used to wake the host processor when motion is detected. The WOM feature can be used to reduce power consumption by putting the host processor to sleep when motion is not detected.
The ICM-20948 has a pedometer feature that can be used to count the number of steps taken by the user. The pedometer feature can be used to track the number of steps taken by the user and to estimate the distance traveled by the user.
You can find the datasheets for the ICM-20948 here:
For migrating from MPU-9250 to ICM-20948, you can refer to the following document:
Thanks and credits to the following sources:
https://wolles-elektronikkiste.de/en/icm-20948-9-axis-sensor-part-i
https://github.com/wollewald/ICM20948_WE/blob/main/src/ICM20948_WE.h
https://github.com/sparkfun/SparkFun_ICM-20948_ArduinoLibrary/tree/main
Example
using Imu = espp::Icm20948<espp::icm20948::Interface::I2C>; // 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; logger.info("Creating I2C on port {} with SDA {} and SCL {}", i2c_port, i2c_sda, i2c_scl); logger.info("I2C clock speed: {} Hz", i2c_clock_speed); 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}); std::vector<uint8_t> found_addresses; for (uint8_t address = 0; address < 128; address++) { if (i2c.probe_device(address)) { found_addresses.push_back(address); } } // print out the addresses that were found logger.info("Found devices at addresses: {::#02x}", found_addresses); // set the address of the IMU uint8_t imu_address = found_addresses[0]; // make the orientation filter to compute orientation from accel + gyro static constexpr float angle_noise = 0.001f; static constexpr float rate_noise = 0.1f; static espp::KalmanFilter<3> 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); auto kalman_filter_fn = [](float dt, const Imu::Value &accel, const Imu::Value &gyro, const Imu::Value &mag) -> Imu::Value { // Apply Kalman filter float accelRoll = atan2(accel.y, accel.z); float accelPitch = atan2(-accel.x, sqrt(accel.y * accel.y + accel.z * accel.z)); // implement yaw from magnetometer float accelYaw = atan2(mag.y, mag.x); kf.predict({espp::deg_to_rad(gyro.x), espp::deg_to_rad(gyro.y), espp::deg_to_rad(gyro.z)}, dt); kf.update({accelRoll, accelPitch, accelYaw}); float roll, pitch, yaw; std::tie(roll, pitch, yaw) = kf.get_state(); // return the computed orientation Imu::Value orientation{}; orientation.roll = roll; orientation.pitch = pitch; orientation.yaw = yaw; return orientation; }; auto madgwick_filter_fn = [](float dt, const Imu::Value &accel, const Imu::Value &gyro, const Imu::Value &mag) -> Imu::Value { // Apply Madgwick filter f.update(dt, accel.x, accel.y, accel.z, espp::deg_to_rad(gyro.x), espp::deg_to_rad(gyro.y), espp::deg_to_rad(gyro.z), mag.x, mag.y, mag.z); float roll, pitch, yaw; f.get_euler(roll, pitch, yaw); // return the computed orientation Imu::Value orientation{}; orientation.pitch = espp::deg_to_rad(pitch); orientation.roll = espp::deg_to_rad(roll); orientation.yaw = espp::deg_to_rad(yaw); return orientation; }; // make the IMU config Imu::Config config{ .device_address = imu_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, .gyroscope_range = Imu::GyroscopeRange::RANGE_250DPS, .accelerometer_sample_rate_divider = 9, // 1kHz / (1 + 9) = 100Hz .gyroscope_sample_rate_divider = 9, // 1kHz / (1 + 9) = 100Hz .magnetometer_mode = Imu::MagnetometerMode::CONTINUOUS_MODE_100_HZ, }, .orientation_filter = kalman_filter_fn, .auto_init = true, }; // create the IMU logger.info("Creating IMU"); Imu imu(config); // 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), " // kalman filter outputs "Kalman Roll (rad), Kalman Pitch (rad), Kalman Yaw (rad), " "Kalman Gravity X, Kalman Gravity Y, Kalman Gravity Z, " // madgwick filter outputs "Madgwick Roll (rad), Madgwick Pitch (rad), Magwick Yaw (rad), " "Madgwick Gravity X, Madgwick Gravity Y, Madgwick Gravity Z\n"); logger.info("Starting IMU timer"); // make a task to read out the IMU data and print it to console espp::Timer imu_timer({.period = 15ms, .callback = [&]() -> bool { 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; // update the imu data if (!imu.update(dt, ec)) { logger.error("Failed to update IMU: {}", ec.message()); return false; } // get accel auto accel = imu.get_accelerometer(); auto gyro = imu.get_gyroscope(); auto mag = imu.get_magnetometer(); auto temp = imu.get_temperature(); auto orientation = imu.get_orientation(); auto gravity_vector = imu.get_gravity_vector(); // 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},", (float)accel.x, (float)accel.y, (float)accel.z); text += fmt::format("{:03.3f},{:03.3f},{:03.3f},", espp::deg_to_rad(gyro.x), espp::deg_to_rad(gyro.y), espp::deg_to_rad(gyro.z)); text += fmt::format("{:02.1f},", temp); // print kalman filter outputs text += fmt::format("{:03.3f},{:03.3f},{:03.3f},", (float)orientation.x, (float)orientation.y, (float)orientation.z); text += fmt::format("{:03.3f},{:03.3f},{:03.3f},", (float)gravity_vector.x, (float)gravity_vector.y, (float)gravity_vector.z); auto madgwick_orientation = madgwick_filter_fn(dt, accel, gyro, mag); float roll = madgwick_orientation.roll; float pitch = madgwick_orientation.pitch; float yaw = madgwick_orientation.yaw; 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},{:03.3f},", roll, pitch, yaw); 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, }}); // loop forever while (true) { std::this_thread::sleep_for(1s); }
- Template Parameters
Interface – The interface type of the ICM20948
Public Types
-
using DutyCycleMode = icm20948::DutyCycleMode
Duty cycle mode.
-
using FifoMode = icm20948::FifoMode
FIFO mode.
-
using FifoType = icm20948::FifoType
FIFO type.
-
using AccelerometerRange = icm20948::AccelerometerRange
Accelerometer range.
-
using GyroscopeRange = icm20948::GyroscopeRange
Gyroscope range.
-
using DmpODR = icm20948::DmpODR
DMP output data rate.
-
using TemperatureFilterBandwidth = icm20948::TemperatureFilterBandwidth
Temperature filter bandwidth.
-
using MagnetometerMode = icm20948::MagnetometerMode
Magnetometer mode.
-
using AccelerometerFilterBandwidth = icm20948::AccelerometerFilterBandwidth
Sensor filter bandwidth for the accelerometer.
-
using GyroscopeFilterBandwidth = icm20948::GyroscopeFilterBandwidth
Sensor filter bandwidth for the gyroscope.
-
using AccelerometerAveraging = icm20948::AccelerometerAveraging
Accelerometer averaging.
-
using GyroscopeAveraging = icm20948::GyroscopeAveraging
Gyroscope averaging.
-
using ImuConfig = icm20948::ImuConfig
IMU configuration.
-
using RawValue = icm20948::RawValue
Raw IMU data.
-
using Value = icm20948::Value
IMU data.
-
typedef std::function<Value(float, const Value&, const Value&, const Value&)> filter_fn
Filter function.
Filter function for filtering 9-axis data into 3-axis orientation data
- Param dt
The time step in seconds
- Param accel
The accelerometer data
- Param gyro
The gyroscope data
- Param mag
The magnetometer data
- Return
The filtered orientation data in radians
-
typedef std::function<bool(uint8_t)> probe_fn
Function to probe the peripheral
- Param address
The address to probe
- Return
True if the peripheral is found at the given address
Public Functions
-
bool init(std::error_code &ec)
Initialize the ICM20948
- Parameters
ec – The error code to set if an error occurs
- Returns
True if the ICM20948 was initialized successfully, false otherwise
-
uint8_t get_device_id(std::error_code &ec)
Get the device ID
- Parameters
ec – The error code to set if an error occurs
- Returns
The device ID
-
bool set_config(const ImuConfig &imu_config, std::error_code &ec)
Set the IMU configuration
- Parameters
imu_config – The IMU configuration
ec – The error code to set if an error occurs
- Returns
True if the configuration was set successfully, false otherwise
-
bool set_i2c_master_enabled(bool enable, std::error_code &ec)
Set whether the I2C master is enabled
- Parameters
enable – True to enable the I2C master, false to disable it
ec – The error code to set if an error occurs
- Returns
True if the I2C master was enabled or disabled successfully, false otherwise
-
bool set_odr_align_enabled(bool enable, std::error_code &ec)
Enable ODR alignment
- Parameters
enable – True to enable ODR alignment, false to disable it
ec – The error code to set if an error occurs
- Returns
True if ODR alignment was enabled or disabled successfully, false otherwise
-
bool set_accelerometer_offsets(const float &x, const float &y, const float &z, std::error_code &ec)
Set the accelerometer offsets
- Parameters
x – The X-axis offset
y – The Y-axis offset
z – The Z-axis offset
ec – The error code to set if an error occurs
- Returns
True if the offsets were set successfully, false otherwise
-
bool get_accelerometer_offsets(float &x, float &y, float &z, std::error_code &ec)
Get the accelerometer offsets
- Parameters
x – The X-axis offset
y – The Y-axis offset
z – The Z-axis offset
ec – The error code to set if an error occurs
- Returns
True if the offsets were retrieved successfully, false otherwise
-
bool set_gyroscope_offsets(const float &x, const float &y, const float &z, std::error_code &ec)
Set the gyroscope offsets
- Parameters
x – The X-axis offset
y – The Y-axis offset
z – The Z-axis offset
ec – The error code to set if an error occurs
- Returns
True if the offsets were set successfully, false otherwise
-
bool get_gyroscope_offsets(float &x, float &y, float &z, std::error_code &ec)
Get the gyroscope offsets
- Parameters
x – The X-axis offset
y – The Y-axis offset
z – The Z-axis offset
ec – The error code to set if an error occurs
- Returns
True if the offsets were retrieved successfully, false otherwise
-
bool set_low_power_enabled(bool enable, std::error_code &ec)
Set whether the ICM20948 is in low power mode
- Parameters
enable – True to enable low power mode, false to disable it
ec – The error code to set if an error occurs
- Returns
True if low power mode was enabled or disabled successfully, false otherwise
-
bool set_low_power_duty_cycle_mode(const DutyCycleMode &mode, std::error_code &ec)
Set the low power duty cycle mode
- Parameters
mode – The duty cycle mode
ec – The error code to set if an error occurs
- Returns
True if the duty cycle mode was set successfully, false otherwise
-
bool set_gyroscope_average_in_low_power_mode(const GyroscopeAveraging &average, std::error_code &ec)
Set the gyroscope average in low power mode
- Parameters
average – The gyroscope averaging
ec – The error code to set if an error occurs
- Returns
True if the gyroscope average was set successfully, false otherwise
-
bool set_accelerometer_average_in_low_power_mode(const AccelerometerAveraging &average, std::error_code &ec)
Set the accelerometer average in low power mode
- Parameters
average – The accelerometer averaging
ec – The error code to set if an error occurs
- Returns
True if the accelerometer average was set successfully, false otherwise
-
bool sleep(bool enable, std::error_code &ec)
Set whether the ICM20948 is in sleep mode
- Parameters
enable – True to enable sleep mode, false to disable it
ec – The error code to set if an error occurs
- Returns
True if sleep mode was enabled or disabled successfully, false otherwise
-
bool reset(std::error_code &ec)
Reset the ICM20948
- Parameters
ec – The error code to set if an error occurs
- Returns
True if the ICM20948 was reset successfully, false otherwise
-
bool enable_accelerometer(bool enable, std::error_code &ec)
Enable or disable the accelerometer
- Parameters
enable – True to enable the accelerometer, false to disable it
ec – The error code to set if an error occurs
- Returns
True if the accelerometer was enabled or disabled successfully, false otherwise
-
float get_accelerometer_sensitivity()
Get the accelerometer sensitivity
- Returns
The accelerometer sensitivity in LSB/g
-
float read_accelerometer_sensitivity(std::error_code &ec)
Read the accelerometer sensitivity
- Parameters
ec – The error code to set if an error occurs
- Returns
The accelerometer sensitivity in LSB/g
-
AccelerometerRange get_accelerometer_range()
Get the accelerometer range
- Returns
The accelerometer range
-
AccelerometerRange read_accelerometer_range(std::error_code &ec)
Read the accelerometer range
- Parameters
ec – The error code to set if an error occurs
- Returns
The accelerometer range
-
bool set_accelerometer_range(const AccelerometerRange &range, std::error_code &ec)
Set the accelerometer range
- Parameters
range – The accelerometer range
ec – The error code to set if an error occurs
- Returns
True if the range was set successfully, false otherwise
-
bool set_accelerometer_dlpf_enabled(bool enable, std::error_code &ec)
Enable or disable the accelerometer digital low pass filter
- Parameters
enable – True to enable the digital low pass filter, false to disable it
ec – The error code to set if an error occurs
- Returns
True if the digital low pass filter was enabled or disabled successfully, false otherwise
-
bool set_accelerometer_dlpf(const AccelerometerFilterBandwidth &bandwidth, std::error_code &ec)
Set the accelerometer digital low pass filter
- Parameters
bandwidth – The filter bandwidth
ec – The error code to set if an error occurs
- Returns
True if the filter bandwidth was set successfully, false otherwise
-
bool set_accelerometer_sample_rate_divider(uint16_t sample_rate_divider, std::error_code &ec)
Set the accelerometer sample rate divider
- Parameters
sample_rate_divider – The sample rate divider
ec – The error code to set if an error occurs
- Returns
True if the sample rate divider was set successfully, false otherwise
-
bool enable_gyroscope(bool enable, std::error_code &ec)
Enable or disable the gyroscope
- Parameters
enable – True to enable the gyroscope, false to disable it
ec – The error code to set if an error occurs
- Returns
True if the gyroscope was enabled or disabled successfully, false otherwise
-
float get_gyroscope_sensitivity()
Get the gyroscope sensitivity
- Returns
The gyroscope sensitivity in LSB/(°/s)
-
float read_gyroscope_sensitivity(std::error_code &ec)
Read the gyroscope sensitivity
- Parameters
ec – The error code to set if an error occurs
- Returns
The gyroscope sensitivity in LSB/(°/s)
-
GyroscopeRange get_gyroscope_range()
Get the gyroscope range
- Returns
The gyroscope range
-
GyroscopeRange read_gyroscope_range(std::error_code &ec)
Read the gyroscope range
- Parameters
ec – The error code to set if an error occurs
- Returns
The gyroscope range
-
bool set_gyroscope_range(const GyroscopeRange &range, std::error_code &ec)
Set the gyroscope range
- Parameters
range – The gyroscope range
ec – The error code to set if an error occurs
- Returns
True if the range was set successfully, false otherwise
-
bool set_gyroscope_dlpf_enabled(bool enable, std::error_code &ec)
Enable or disable the gyroscope digital low pass filter
- Parameters
enable – True to enable the digital low pass filter, false to disable it
ec – The error code to set if an error occurs
- Returns
True if the digital low pass filter was enabled or disabled successfully, false otherwise
-
bool set_gyroscope_dlpf(const GyroscopeFilterBandwidth &bandwidth, std::error_code &ec)
Set the gyroscope digital low pass filter
- Parameters
bandwidth – The filter bandwidth
ec – The error code to set if an error occurs
- Returns
True if the filter bandwidth was set successfully, false otherwise
-
bool set_gyroscope_sample_rate_divider(uint8_t sample_rate_divider, std::error_code &ec)
Set the gyroscope sample rate divider
- Parameters
sample_rate_divider – The sample rate divider
ec – The error code to set if an error occurs
- Returns
True if the sample rate divider was set successfully, false otherwise
-
bool set_temperature_dlpf(const TemperatureFilterBandwidth &bandwidth, std::error_code &ec)
Set the temperature digital low pass filter
- Parameters
bandwidth – The filter bandwidth
ec – The error code to set if an error occurs
- Returns
True if the filter bandwidth was set successfully, false otherwise
-
bool init_magnetometer(std::error_code &ec)
Initialize the magnetometer
- Parameters
ec – The error code to set if an error occurs
- Returns
True if the magnetometer was initialized successfully, false otherwise
-
uint16_t get_magnetometer_device_id(std::error_code &ec)
Get the magnetometer device ID
- Parameters
ec – The error code to set if an error occurs
- Returns
The device ID
-
bool set_magnetometer_mode(const icm20948::MagnetometerMode &mode, std::error_code &ec)
Set the magnetometer mode
- Parameters
mode – The magnetometer mode
ec – The error code to set if an error occurs
- Returns
True if the mode was set successfully, false otherwise
-
float get_magnetometer_sensitivity()
Get the magnetometer sensitivity
- Returns
The magnetometer sensitivity in µT/LSB
-
bool reset_magnetometer(std::error_code &ec)
Reset the magnetometer
- Parameters
ec – The error code to set if an error occurs
- Returns
True if the magnetometer was reset successfully, false otherwise
-
Value get_accelerometer()
Get the raw accelerometer data
Note
This returns the most recent data, not the data at the time of the call. It is refreshed when update or read_accelerometer is called.
- Returns
The raw accelerometer data
-
Value get_gyroscope()
Get the raw gyroscope data
Note
This returns the most recent data, not the data at the time of the call. It is refreshed when update or read_gyroscope is called.
- Returns
The raw gyroscope data
-
Value get_magnetometer()
Get the raw magnetometer data
Note
This returns the most recent data, not the data at the time of the call. It is refreshed when update or read_magnetometer is called.
- Returns
The raw magnetometer data
-
float get_temperature()
Get the raw temperature data
Note
This returns the most recent data, not the data at the time of the call. It is refreshed when update or read_temperature is called.
- Returns
The raw temperature data
-
Value read_accelerometer(std::error_code &ec)
Read the raw accelerometer data
- Parameters
ec – The error code to set if an error occurs
- Returns
The raw accelerometer data
-
Value read_gyroscope(std::error_code &ec)
Read the raw gyroscope data
- Parameters
ec – The error code to set if an error occurs
- Returns
The raw gyroscope data
-
Value read_magnetometer(std::error_code &ec)
Read the raw magnetometer data
- Parameters
ec – The error code to set if an error occurs
- Returns
The raw magnetometer data
-
float read_temperature(std::error_code &ec)
Read the raw temperature data
- Parameters
ec – The error code to set if an error occurs
- Returns
The raw temperature data
-
bool enable_dmp(bool enable, std::error_code &ec)
Enable or disable the DMP
- Parameters
enable – True to enable the DMP, false to disable it
ec – The error code to set if an error occurs
- Returns
True if the DMP was enabled or disabled successfully, false otherwise
-
bool reset_dmp(std::error_code &ec)
Reset the DMP
- Parameters
ec – The error code to set if an error occurs
- Returns
True if the DMP was reset successfully, false otherwise
-
bool update(float dt, std::error_code &ec)
Update the accelerometer, gyroscope, temperature, and magnetometer values
Note
The values can be retrieved with get_accelerometer_values and get_gyroscope_values, and the temperature can be retrieved with get_temperature. The orientation can be retrieved with get_orientation.
- Parameters
dt – The time step in seconds
ec – The error code to set if an error occurs
- Returns
True if the values were updated successfully, false otherwise
-
Value get_orientation()
Get the orientation
Note
The orientation is calculated using the accelerometer, gyroscope, and magnetometer data. The orientation is filtered using the orientation filter function. It is updated each time update is called.
- Returns
The orientation in radians
-
Value get_gravity_vector()
Get the gravity vector
Note
The gravity vector is calculated using the accelerometer data. It is updated each time update is called.
- Returns
The gravity vector
-
float get_pitch()
Get the pitch angle
- Returns
The pitch angle in radians
-
float get_roll()
Get the roll angle
- Returns
The roll angle in radians
-
float get_yaw()
Get the yaw angle
- Returns
The yaw angle in radians
-
bool enable_fifo(bool enable, std::error_code &ec)
Enable or disable the FIFO
- Parameters
enable – True to enable the FIFO, false to disable it
ec – The error code to set if an error occurs
- Returns
True if the FIFO was enabled or disabled successfully, false otherwise
-
bool set_fifo_mode(const FifoMode &mode, std::error_code &ec)
Set the FIFO mode
- Parameters
mode – The FIFO mode
ec – The error code to set if an error occurs
- Returns
True if the FIFO mode was set successfully, false otherwise
-
bool start_fifo(const FifoType &fifo_type, std::error_code &ec)
Start the FIFO
- Parameters
fifo_type – The FIFO type
ec – The error code to set if an error occurs
- Returns
True if the FIFO was started successfully, false otherwise
-
bool stop_fifo(std::error_code &ec)
Stop the FIFO
- Parameters
ec – The error code to set if an error occurs
- Returns
True if the FIFO was stopped successfully, false otherwise
-
bool reset_fifo(std::error_code &ec)
Reset the FIFO
- Parameters
ec – The error code to set if an error occurs
- Returns
True if the FIFO was reset successfully, false otherwise
-
uint16_t get_fifo_count(std::error_code &ec)
Get the FIFO count
- Parameters
ec – The error code to set if an error occurs
- Returns
The FIFO count
-
inline bool probe(std::error_code &ec)
Probe the peripheral
Note
This function is thread safe
Note
If the probe function is not set, this function will return false and set the error code to operation_not_supported
Note
This function is only available if UseAddress is true
- Parameters
ec – The error code to set if there is an error
- Returns
True if the peripheral is found
-
inline void set_address(uint8_t address)
Set the address of the peripheral
Note
This function is thread safe
Note
This function is only available if UseAddress is true
- Parameters
address – The address of the peripheral
-
inline void set_probe(const probe_fn &probe)
Set the probe function
Note
This function is thread safe
Note
This should rarely be used, as the probe function is usually set in the constructor. If you need to change the probe function, consider using the set_config function instead.
Note
This function is only available if UseAddress is true
- Parameters
probe – The probe function
-
inline void set_write(const write_fn &write)
Set the write function
Note
This function is thread safe
Note
This should rarely be used, as the write function is usually set in the constructor. If you need to change the write function, consider using the set_config function instead.
- Parameters
write – The write function
-
inline void set_read(const read_fn &read)
Set the read function
Note
This function is thread safe
Note
This should rarely be used, as the read function is usually set in the constructor. If you need to change the read function, consider using the set_config function instead.
- Parameters
read – The read function
-
inline void set_read_register(const read_register_fn &read_register)
Set the read register function
Note
This function is thread safe
Note
This should rarely be used, as the read register function is usually set in the constructor. If you need to change the read register function, consider using the set_config function instead.
- Parameters
read_register – The read register function
-
inline void set_write_then_read(const write_then_read_fn &write_then_read)
Set the write then read function
Note
This function is thread safe
Note
This should rarely be used, as the write then read function is usually set in the constructor. If you need to change the write then
- Parameters
write_then_read – The write then read function
-
inline void set_separate_write_then_read_delay(const std::chrono::milliseconds &delay)
Set the delay between the write and read operations in write_then_read
Note
This function is thread safe
Note
This should rarely be used, as the delay is usually set in the constructor. If you need to change the delay, consider using the set_config function instead.
Note
This delay is only used if the write_then_read function is not set to a custom function and the write and read functions are separate functions.
- Parameters
delay – The delay between the write and read operations in write_then_read
-
inline void set_config(const Config &config)
Set the configuration for the peripheral
Note
This function is thread safe
Note
The configuration should normally be set in the constructor, but this function can be used to change the configuration after the peripheral has been created - for instance if the peripheral could be found on different communications buses.
- Parameters
config – The configuration for the peripheral
-
inline void set_config(Config &&config)
Set the configuration for the peripheral
Note
This function is thread safe
Note
The configuration should normally be set in the constructor, but this function can be used to change the configuration after the peripheral has been created - for instance if the peripheral could be found on different communications buses.
- Parameters
config – The configuration for the peripheral
-
inline const std::string &get_name() const
Get the name of the component
Note
This is the tag of the logger
- Returns
A const reference to the name of the component
-
inline void set_log_tag(const std::string_view &tag)
Set the tag for the logger
- Parameters
tag – The tag to use for the logger
-
inline espp::Logger::Verbosity get_log_level() const
Get the log level for the logger
See also
See also
- Returns
The verbosity level of the logger
-
inline void set_log_level(espp::Logger::Verbosity level)
Set the log level for the logger
See also
See also
- Parameters
level – The verbosity level to use for the logger
-
inline void set_log_verbosity(espp::Logger::Verbosity level)
Set the log verbosity for the logger
See also
See also
See also
Note
This is a convenience method that calls set_log_level
- Parameters
level – The verbosity level to use for the logger
-
inline espp::Logger::Verbosity get_log_verbosity() const
Get the log verbosity for the logger
See also
See also
See also
Note
This is a convenience method that calls get_log_level
- Returns
The verbosity level of the logger
-
inline void set_log_rate_limit(std::chrono::duration<float> rate_limit)
Set the rate limit for the logger
See also
Note
Only calls to the logger that have _rate_limit suffix will be rate limited
- Parameters
rate_limit – The rate limit to use for the logger
Public Static Attributes
-
static constexpr uint8_t DEFAULT_ADDRESS = 0x68
Default I2C address of the ICM20948 with AD0 low.
-
static constexpr uint8_t DEFAULT_ADDRESS_AD0_HIGH = 0x69
Default I2C address of the ICM20948 with AD0 high.
-
static constexpr uint8_t AK09916C_ADDRESS = 0x0C
I2C address of the AK09916C magnetometer.
-
struct Config
Configuration struct for the ICM20948.
Public Members
-
uint8_t device_address = DEFAULT_ADDRESS
I2C address of the ICM20948.
-
BasePeripheral<uint8_t, Interface == icm20948::Interface::I2C>::write_fn write = nullptr
Write function.
-
BasePeripheral<uint8_t, Interface == icm20948::Interface::I2C>::read_fn read = nullptr
Read function.
-
bool auto_init = {true}
Automatically initialize the ICM20948.
-
uint8_t device_address = DEFAULT_ADDRESS
Header File
Unions
- espp::icm20948::Value.__unnamed138__