maix::ahrs

maix.ahrs module

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

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

Module

No module

Enum

Variable

PI

Math PI

item description
value 3.14159265358979323846f
readonly True

C++ defination code:

const float PI = 3.14159265358979323846f

RAD2DEG

angle unit radian to degree.

item description
value 180.0f / PI
readonly True

C++ defination code:

const float RAD2DEG = 180.0f / PI

DEG2RAD

angle unit degree to radian.

item description
value PI / 180.0f
readonly True

C++ defination code:

const float DEG2RAD = PI / 180.0f

Function

Class

MahonyAHRS

class MahonyAHRS for Attitude Estimation from IMU data, a Complementary Filter,\nsupport accelerometer, gyroscope and magnetometer fusion.

C++ defination code:

class MahonyAHRS

kp

P of PI controller, a larger P (proportional gain) leads to faster response,\nbut it increases the risk of overshoot and oscillation.

item description
type var
static False
readonly False

C++ defination code:

float kp

ki

I of PI controller, a larger I (integral gain) helps to eliminate steady-state errors more quickly,\nbut it can accumulate error over time, potentially causing instability or slow drift.

item description
type var
static False
readonly False

C++ defination code:

float ki

MahonyAHRS

class MahonyAHRS constructor.

item description
type func
param kp: P of PI controller, a larger P (proportional gain) leads to faster response,
but it increases the risk of overshoot and oscillation.
ki: I of PI controller, a larger I (integral gain) helps to eliminate steady-state errors more quickly,
but it can accumulate error over time, potentially causing instability or slow drift.
static False

C++ defination code:

MahonyAHRS(float kp,float ki)

init

Initialize by accelerometer and magnetometer(optional).\nIf you not call this method mannually, get_angle and update method will automatically call it.

item description
type func
param ax: z axis of accelerometer, unit is g or raw data.
ay: y axis of accelerometer, unit is g or raw data.
mx: x axis of magnetometer, unit is uT or raw data, mx, my, mz all 0 means not use magnetometer.
my: y axis of magnetometer, unit is uT or raw data, mx, my, mz all 0 means not use magnetometer.
mz: z axis of magnetometer, unit is uT or raw data, mx, my, mz all 0 means not use magnetometer.
static False

C++ defination code:

void init(float ax, float ay, float az, float mx = 0, float my = 0, float mz = 0)

update

Update angles by accelerometer, gyroscope and magnetometer(optional).\nget_angle method will automatically call it.

item description
type func
param ax: z axis of gyroscope, unit is rad/s.
ay: y axis of gyroscope, unit is rad/s.
mx: x axis of magnetometer, unit is uT or raw data, mx, my, mz all 0 means not use magnetometer.
my: y axis of magnetometer, unit is uT or raw data, mx, my, mz all 0 means not use magnetometer.
mz: z axis of magnetometer, unit is uT or raw data, mx, my, mz all 0 means not use magnetometer.
dt: Delta time between two times call update method.
static False

C++ defination code:

void update(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz, float dt)

get_angle

Get angle by mahony complementary filter, will automatically call update method,\nand automatically call init in first time.

item description
type func
param acc: accelerometer data, unit is g or raw data. maix.Vector3f type.
gyro: gyroscope data, unit can be rad/s or degree/s, if rad/s, arg radian should be true. maix.Vector3f type.
mag: magnetometer data, optional, if no magnetometer, set all value to 0. maix.Vector3f type.
dt: delta T of two time call get_anle, unit is second, float type.
radian: if gyro's unit is rad/s, set this arg to true, degree/s set to false.
return rotation angle data, maix.Vector3f type.
static False

C++ defination code:

Vector3f get_angle(Vector3f acc, Vector3f gyro,Vector3f mag, float dt, bool radian = false)

reset

reset to not initialized status.

item description
type func
static False

C++ defination code:

void reset()