maix::ext_dev::imu

maix.ext_dev.imu module

This is maix::ext_dev::imu module of MaixCDK.
All of these elements are in namespace maix::ext_dev::imu.

For MaixCDK developer: DO NOT edit this doc file manually, this doc is auto generated!

Module

No module

Enum

Mode

imu mode

item describe
values ACC_ONLY:
GYRO_ONLY:
DUAL:

C++ defination code:

enum class Mode {
    ACC_ONLY = 0,
    GYRO_ONLY,
    DUAL
}

AccScale

imu acc scale

item describe
values ACC_SCALE_2G:
ACC_SCALE_4G:
ACC_SCALE_8G:
ACC_SCALE_16G:

C++ defination code:

enum class AccScale {
    ACC_SCALE_2G = 0,
    ACC_SCALE_4G,
    ACC_SCALE_8G,
    ACC_SCALE_16G
}

AccOdr

imu acc output data rate

item describe
values ACC_ODR_8000: Accelerometer ODR set to 8000 Hz.
ACC_ODR_4000: Accelerometer ODR set to 4000 Hz.
ACC_ODR_2000: Accelerometer ODR set to 2000 Hz.
ACC_ODR_1000: Accelerometer ODR set to 1000 Hz.
ACC_ODR_500: Accelerometer ODR set to 500 Hz.
ACC_ODR_250: Accelerometer ODR set to 250 Hz.
ACC_ODR_125: Accelerometer ODR set to 125 Hz.
ACC_ODR_62_5: Accelerometer ODR set to 62.5 Hz.
ACC_ODR_31_25: Accelerometer ODR set to 31.25 Hz.
ACC_ODR_128: Accelerometer ODR set to 128 Hz.
ACC_ODR_21: Accelerometer ODR set to 21 Hz.
ACC_ODR_11: Accelerometer ODR set to 11 Hz.
ACC_ODR_3: Accelerometer ODR set to 3 Hz.

C++ defination code:

enum class AccOdr {
    ACC_ODR_8000,      // Accelerometer ODR set to 8000 Hz.
    ACC_ODR_4000,      // Accelerometer ODR set to 4000 Hz.
    ACC_ODR_2000,      // Accelerometer ODR set to 2000 Hz.
    ACC_ODR_1000,      // Accelerometer ODR set to 1000 Hz.
    ACC_ODR_500,       // Accelerometer ODR set to 500 Hz.
    ACC_ODR_250,       // Accelerometer ODR set to 250 Hz.
    ACC_ODR_125,       // Accelerometer ODR set to 125 Hz.
    ACC_ODR_62_5,      // Accelerometer ODR set to 62.5 Hz.
    ACC_ODR_31_25,     // Accelerometer ODR set to 31.25 Hz.
    ACC_ODR_128 = 12,  // Accelerometer ODR set to 128 Hz.
    ACC_ODR_21,        // Accelerometer ODR set to 21 Hz.
    ACC_ODR_11,        // Accelerometer ODR set to 11 Hz.
    ACC_ODR_3,         // Accelerometer ODR set to 3 Hz.
}

GyroScale

imu gyro scale

item describe
values GYRO_SCALE_16DPS: Gyroscope scale set to ±16 degrees per second.
GYRO_SCALE_32DPS: Gyroscope scale set to ±32 degrees per second.
GYRO_SCALE_64DPS: Gyroscope scale set to ±64 degrees per second.
GYRO_SCALE_128DPS: Gyroscope scale set to ±128 degrees per second.
GYRO_SCALE_256DPS: Gyroscope scale set to ±256 degrees per second.
GYRO_SCALE_512DPS: Gyroscope scale set to ±512 degrees per second.
GYRO_SCALE_1024DPS: Gyroscope scale set to ±1024 degrees per second.
GYRO_SCALE_2048DPS: Gyroscope scale set to ±2048 degrees per second.

C++ defination code:

enum class GyroScale {
    GYRO_SCALE_16DPS = 0,       // Gyroscope scale set to ±16 degrees per second.
    GYRO_SCALE_32DPS,            // Gyroscope scale set to ±32 degrees per second.
    GYRO_SCALE_64DPS,            // Gyroscope scale set to ±64 degrees per second.
    GYRO_SCALE_128DPS,           // Gyroscope scale set to ±128 degrees per second.
    GYRO_SCALE_256DPS,           // Gyroscope scale set to ±256 degrees per second.
    GYRO_SCALE_512DPS,           // Gyroscope scale set to ±512 degrees per second.
    GYRO_SCALE_1024DPS,          // Gyroscope scale set to ±1024 degrees per second.
    GYRO_SCALE_2048DPS,          // Gyroscope scale set to ±2048 degrees per second.
}

GyroOdr

imu gyro output data rate

item describe
values GYRO_ODR_8000: Gyroscope ODR set to 8000 Hz.
GYRO_ODR_4000: Gyroscope ODR set to 4000 Hz.
GYRO_ODR_2000: Gyroscope ODR set to 2000 Hz.
GYRO_ODR_1000: Gyroscope ODR set to 1000 Hz.
GYRO_ODR_500: Gyroscope ODR set to 500 Hz.
GYRO_ODR_250: Gyroscope ODR set to 250 Hz.
GYRO_ODR_125: Gyroscope ODR set to 125 Hz.
GYRO_ODR_62_5: Gyroscope ODR set to 62.5 Hz.
GYRO_ODR_31_25: Gyroscope ODR set to 31.25 Hz.

C++ defination code:

enum class GyroOdr {
    GYRO_ODR_8000,     // Gyroscope ODR set to 8000 Hz.
    GYRO_ODR_4000,     // Gyroscope ODR set to 4000 Hz.
    GYRO_ODR_2000,     // Gyroscope ODR set to 2000 Hz.
    GYRO_ODR_1000,     // Gyroscope ODR set to 1000 Hz.
    GYRO_ODR_500,      // Gyroscope ODR set to 500 Hz.
    GYRO_ODR_250,      // Gyroscope ODR set to 250 Hz.
    GYRO_ODR_125,      // Gyroscope ODR set to 125 Hz.
    GYRO_ODR_62_5,     // Gyroscope ODR set to 62.5 Hz.
    GYRO_ODR_31_25,    // Gyroscope ODR set to 31.25 Hz.
}

Variable

Function

Class

IMU

QMI8656 driver class

C++ defination code:

class IMU

__init__

Construct a new IMU object, will open IMU

item description
type func
param driver: driver name, only support "qmi8656"
i2c_bus: i2c bus number. Automatically selects the on-board imu when -1 is passed in.
addr: IMU i2c addr.
freq: IMU freq
mode: IMU Mode: ACC_ONLY/GYRO_ONLY/DUAL
acc_scale: acc scale, see @imu::AccScale
acc_odr: acc output data rate, see @imu::AccOdr
gyro_scale: gyro scale, see @imu::GyroScale
gyro_odr: gyro output data rate, see @imu::GyroOdr
block: block or non-block, defalut is true
static False

C++ defination code:

IMU(std::string driver, int i2c_bus=-1, int addr=0x6B, int freq=400000,
            maix::ext_dev::imu::Mode mode=maix::ext_dev::imu::Mode::DUAL,
            maix::ext_dev::imu::AccScale acc_scale=maix::ext_dev::imu::AccScale::ACC_SCALE_2G,
            maix::ext_dev::imu::AccOdr acc_odr=maix::ext_dev::imu::AccOdr::ACC_ODR_8000,
            maix::ext_dev::imu::GyroScale gyro_scale=maix::ext_dev::imu::GyroScale::GYRO_SCALE_16DPS,
            maix::ext_dev::imu::GyroOdr gyro_odr=maix::ext_dev::imu::GyroOdr::GYRO_ODR_8000,
            bool block=true)

read

Read data from IMU.

item description
type func
return list type. If only one of the outputs is initialized, only [x,y,z] of that output will be returned.
If all outputs are initialized, [acc_x, acc_y, acc_z, gyro_x, gyro_y, gyro_z] is returned.
static False

C++ defination code:

std::vector<float> read()

calculate_calibration

Caculate calibration, save calibration data to /maixapp/shart/imu_calibration

item description
type func
param time_ms: caculate max time, unit:ms
return err::Err
static False

C++ defination code:

err::Err calculate_calibration(uint64_t time_ms = 30 * 1000)

get_calibration

Get calibration data

item description
type func
return return an array, format is [acc_x_bias, acc_y_bias, acc_z_bias, gyro_x_bias, gyro_y_bias, gyro_z_bias]
If the calibration file cannot be found, an empty array will be returned.
static False

C++ defination code:

std::vector<double> get_calibration()

Gcsv

Gcsv class

C++ defination code:

class Gcsv

__init__

Construct a new IMU object

item description
type func
static False

C++ defination code:

Gcsv()

open

Open a file

item description
type func
param path: the path where data will be saved
tscale: time scale, default is 0.001
gscale: gyroscope scale factor, default is 1, unit:g
ascale: accelerometer scale factor, default is 1, unit:radians/second
mscale: magnetometer scale factor, default is 1(unused)
version: version number, default is "1.3"
id: identifier for the IMU, default is "imu"
orientation: sensor orientation, default is "YxZ"
return error code
static False

C++ defination code:

err::Err open(std::string path, double tscale = 0.001, double gscale = 1, double ascale = 1, double mscale = 1, std::string version = "1.3", std::string id = "imu", std::string orientation = "YxZ")

close

Close file

item description
type func
return error code
static False

C++ defination code:

err::Err close()

is_opened

Check if the object is already open

item description
type func
return true, opened; false, not opened
static False

C++ defination code:

bool is_opened()

write

Write imu data to gcsv file

item description
type func
param t: Timestamp of the current data. The actual value is equal to t * tscale. unit:s
gyro: Gyroscope data must be an array consisting of x, y, and z-axis data. The actual value is equal to gyro * gscale. unit:g
acc: Acceleration data must be an array consisting of x, y, and z-axis data. The actual value is equal to acc * ascale.unit:radians/second
mag: Magnetic data must be an array consisting of x, y, and z-axis data. Currently not supported.
static False

C++ defination code:

err::Err write(double timestamp, std::vector<double> gyro, std::vector<double> acc, std::vector<double> mag = std::vector<double>())