Skip to content

Instantly share code, notes, and snippets.

@gamblor21
Created February 18, 2022 14:44
Show Gist options
  • Save gamblor21/9e4b9f2233acb30e3e5e5cdc8149be8a to your computer and use it in GitHub Desktop.
Save gamblor21/9e4b9f2233acb30e3e5e5cdc8149be8a to your computer and use it in GitHub Desktop.
CircuitPython Natmod test
##
## This test file has calibration values for my device
## Anyone else will have to calibrate and set their own values
##
## Only calibrates for the gryo and hardiron offsets
## Set to run on the Adafruit LSM9DS1 over I2C cause that is what I have
##
import time
import board
import busio
import adafruit_lsm9ds1
import madgwick
import ahrs
PRINT_DELAY = 0.1
BETWEEN_READINGS = 1#6500000
BETA = 1.1
MAG_MIN = [-0.5915, 0.01554, -0.57932]
MAG_MAX = [0.39298, 0.99106, 0.4039]
#Uncalibrated gyro: (5.59734e-05, 0.000988863, -0.000842266)
#Gyro: (0.0101819, 0.00204646, 0.010178)
## Used to calibrate the magenetic sensor
def map_range(x, in_min, in_max, out_min, out_max):
"""
Maps a number from one range to another.
:return: Returns value mapped to new range
:rtype: float
"""
mapped = (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min
if out_min <= out_max:
return max(min(mapped, out_max), out_min)
return min(max(mapped, out_max), out_min)
## create the ahrs_filter
#ahrs_filter = mahony.Mahony(50, 5, 100)
# create the sensor
i2c = board.I2C()
sensor = adafruit_lsm9ds1.LSM9DS1_I2C(i2c)
def NativeTest():
#ahrs_filter = madgwick.Madgwick(beta=0.7, sample_freq=42)
ahrs.init(BETA) # beta
ahrs.begin(250) # sample Freq
count = 0 # used to count how often we are feeding the ahrs_filter
lastPrint = time.monotonic() # last time we printed the yaw/pitch/roll values
timestamp = time.monotonic_ns() # used to tune the frequency to approx 100 Hz
ax = ay = az = gx = gy = gz = mx = my = mz = 0.0
while True:
# on an Feather M4 approx time to wait between readings
if (time.monotonic_ns() - timestamp) > BETWEEN_READINGS:
# read the magenetic sensor
mx, my, mz = sensor.magnetic
# adjust for magnetic calibration - hardiron only
# calibration varies per device and physical location
mx = map_range(mx, MAG_MIN[0], MAG_MAX[0], -1, 1)
my = map_range(my, MAG_MIN[1], MAG_MAX[1], -1, 1)
mz = map_range(mz, MAG_MIN[2], MAG_MAX[2], -1, 1)
# read the gyroscope
gx, gy, gz = sensor.gyro
# adjust for my gyro calibration values
# calibration varies per device and physical location
gx -= 0.5833
gy -= 0.1172
gz -= 0.5831
#Gyro: (0.0101819, 0.00204646, 0.010178)
# read the accelerometer
ax, ay, az = sensor.acceleration
# update the ahrs_filter with the values
# gz and my are negative based on my installation
ahrs.update(gx, gy, -gz, ax, ay, az, mx, -my, mz)
count += 1
timestamp = time.monotonic_ns()
# every 0.1 seconds print the ahrs_filter values
if time.monotonic() > lastPrint + PRINT_DELAY:
# ahrs_filter values are in radians/sec multiply by 57.20578 to get degrees/sec
yaw = ahrs.getyaw()
if yaw < 0: # adjust yaw to be between 0 and 360
yaw += 360
#print("Orientation: ",yaw,", ",ahrs.getpitch(),", ",ahrs.getroll(),"Count: ", count)
print((yaw, ahrs.getpitch(), ahrs.getroll(), count))
count = 0 # reset count
lastPrint = time.monotonic()
def PythonTest():
ahrs_filter = madgwick.Madgwick(beta=BETA, sample_freq=190)
count = 0 # used to count how often we are feeding the ahrs_filter
lastPrint = time.monotonic() # last time we printed the yaw/pitch/roll values
timestamp = time.monotonic_ns() # used to tune the frequency to approx 100 Hz
while True:
# on an Feather M4 approx time to wait between readings
if (time.monotonic_ns() - timestamp) > BETWEEN_READINGS:
# read the magenetic sensor
mx, my, mz = sensor.magnetic
# adjust for magnetic calibration - hardiron only
# calibration varies per device and physical location
mx = map_range(mx, MAG_MIN[0], MAG_MAX[0], -1, 1)
my = map_range(my, MAG_MIN[1], MAG_MAX[1], -1, 1)
mz = map_range(mz, MAG_MIN[2], MAG_MAX[2], -1, 1)
# read the gyroscope
gx, gy, gz = sensor.gyro
# adjust for my gyro calibration values
# calibration varies per device and physical location
gx -= 1.1250
gy -= 3.8732
gz += 1.2834
# read the accelerometer
ax, ay, az = sensor.acceleration
# update the ahrs_filter with the values
# gz and my are negative based on my installation
ahrs_filter.update(gx, gy, -gz, ax, ay, az, mx, -my, mz)
count += 1
timestamp = time.monotonic_ns()
# every 0.1 seconds print the ahrs_filter values
if time.monotonic() > lastPrint + PRINT_DELAY:
# ahrs_filter values are in radians/sec multiply by 57.20578 to get degrees/sec
yaw = ahrs_filter.yaw * 57.20578
if yaw < 0: # adjust yaw to be between 0 and 360
yaw += 360
#print("Orientation: ",yaw,", ",ahrs_filter.pitch * 57.29578,", ",ahrs_filter.roll * 57.29578,"Count: ", count)
print((yaw, ahrs_filter.pitch, ahrs_filter.roll, count))
count = 0 # reset count
lastPrint = time.monotonic()
//=============================================================================================
// Madgwick.c
//=============================================================================================
//
// Implementation of Madgwick's IMU and AHRS algorithms.
// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/
//
// From the x-io website "Open-source resources available on this website are
// provided under the GNU General Public Licence unless an alternative licence
// is provided in source."
//
// Date Author Notes
// 29/09/2011 SOH Madgwick Initial release
// 02/10/2011 SOH Madgwick Optimised for reduced CPU load
// 19/02/2012 SOH Madgwick Magnetometer measurement is normalised
//
//=============================================================================================
//-------------------------------------------------------------------------------------------
// Header files
#include "py/dynruntime.h"
#include <math.h>
//-------------------------------------------------------------------------------------------
// Definitions
#define sampleFreqDef 512.0f // sample frequency in Hz
#define betaDef 0.1f // 2 * proportional gain
float beta; // algorithm gain
float q0;
float q1;
float q2;
float q3; // quaternion of sensor frame relative to auxiliary frame
float invSampleFreq;
float roll, pitch, yaw;
float grav[3];
bool anglesComputed = 0;
void Adafruit_Madgwick_Init(float gain) {
beta = gain;
q0 = 1.0f;
q1 = 0.0f;
q2 = 0.0f;
q3 = 0.0f;
invSampleFreq = 1.0f / sampleFreqDef;
anglesComputed = false;
}
STATIC mp_obj_t init(mp_obj_t gain_obj) {
mp_float_t gain = mp_obj_get_float(gain_obj);
Adafruit_Madgwick_Init(gain);
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(init_obj, init);
void Adafruit_Madgwick_begin(float sampleFrequency) {
invSampleFreq = 1.0f / sampleFrequency;
}
STATIC mp_obj_t begin(mp_obj_t sampleFrequency_obj) {
mp_float_t sampleFrequency = mp_obj_get_float(sampleFrequency_obj);
Adafruit_Madgwick_begin(sampleFrequency);
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(begin_obj, begin);
static float Adafruit_Madgwick_invSqrt(float x);
void Adafruit_Madgwick_computeAngles();
void Adafruit_Madgwick_update(float gx, float gy, float gz, float ax, float ay, float az,
float mx, float my, float mz);
void Adafruit_Madgwick_update_dt(float gx, float gy, float gz, float ax, float ay, float az,
float mx, float my, float mz, float dt);
void Adafruit_Madgwick_updateIMU(float gx, float gy, float gz, float ax, float ay, float az);
void Adafruit_Madgwick_updateIMU_dt(float gx, float gy, float gz, float ax, float ay, float az,
float dt);
//============================================================================================
// Functions
float Adafruit_Madgwick_getBeta() {
return beta;
}
STATIC mp_obj_t getBeta(void) {
return mp_obj_new_float(beta);
}
STATIC MP_DEFINE_CONST_FUN_OBJ_0(getBeta_obj, getBeta);
void Adafruit_Madgwick_setBeta(float b) {
beta = b;
}
STATIC mp_obj_t setBeta(mp_obj_t beta_obj) {
mp_float_t b_float = mp_obj_get_float(beta_obj);
Adafruit_Madgwick_setBeta(b_float);
return mp_const_none;
}
STATIC MP_DEFINE_CONST_FUN_OBJ_1(setBeta_obj, setBeta);
float Adafruit_Madgwick_getRoll() {
if (!anglesComputed)
Adafruit_Madgwick_computeAngles();
return roll * 57.29578f;
}
STATIC mp_obj_t getRoll(void) {
return mp_obj_new_float(Adafruit_Madgwick_getRoll());
}
STATIC MP_DEFINE_CONST_FUN_OBJ_0(getRoll_obj, getRoll);
float Adafruit_Madgwick_getPitch() {
if (!anglesComputed)
Adafruit_Madgwick_computeAngles();
return pitch * 57.29578f;
}
STATIC mp_obj_t getPitch(void) {
return mp_obj_new_float(Adafruit_Madgwick_getPitch());
}
STATIC MP_DEFINE_CONST_FUN_OBJ_0(getPitch_obj, getPitch);
float Adafruit_Madgwick_getYaw() {
if (!anglesComputed)
Adafruit_Madgwick_computeAngles();
return yaw * 57.29578f + 180.0f;
}
STATIC mp_obj_t getYaw(void) {
return mp_obj_new_float(Adafruit_Madgwick_getYaw());
}
STATIC MP_DEFINE_CONST_FUN_OBJ_0(getYaw_obj, getYaw);
float getRollRadians() {
if (!anglesComputed)
Adafruit_Madgwick_computeAngles();
return roll;
}
float getPitchRadians() {
if (!anglesComputed)
Adafruit_Madgwick_computeAngles();
return pitch;
}
float getYawRadians() {
if (!anglesComputed)
Adafruit_Madgwick_computeAngles();
return yaw;
}
void getQuaternion(float *w, float *x, float *y, float *z) {
*w = q0;
*x = q1;
*y = q2;
*z = q3;
}
void setQuaternion(float w, float x, float y, float z) {
q0 = w;
q1 = x;
q2 = y;
q3 = z;
}
void getGravityVector(float *x, float *y, float *z) {
if (!anglesComputed)
Adafruit_Madgwick_computeAngles();
*x = grav[0];
*y = grav[1];
*z = grav[2];
}
void Adafruit_Madgwick_update_dt(float gx, float gy, float gz, float ax, float ay,
float az, float mx, float my, float mz,
float dt) {
float recipNorm;
float s0, s1, s2, s3;
float qDot1, qDot2, qDot3, qDot4;
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;
// Use IMU algorithm if magnetometer measurement invalid (avoids NaN in
// magnetometer normalisation)
if ((mx == 0.0f) && (my == 0.0f) && (mz == 0.0f)) {
Adafruit_Madgwick_updateIMU_dt(gx, gy, gz, ax, ay, az, dt);
return;
}
// Convert gyroscope degrees/sec to radians/sec
gx *= 0.0174533f;
gy *= 0.0174533f;
gz *= 0.0174533f;
// 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))) {
// Normalise accelerometer measurement
recipNorm = Adafruit_Madgwick_invSqrt(ax * ax + ay * ay + az * az);
ax *= recipNorm;
ay *= recipNorm;
az *= recipNorm;
// Normalise magnetometer measurement
recipNorm = Adafruit_Madgwick_invSqrt(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 = MICROPY_FLOAT_C_FUN(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 = Adafruit_Madgwick_invSqrt(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 = Adafruit_Madgwick_invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
q0 *= recipNorm;
q1 *= recipNorm;
q2 *= recipNorm;
q3 *= recipNorm;
anglesComputed = 0;
}
//-------------------------------------------------------------------------------------------
// IMU algorithm update
void Adafruit_Madgwick_updateIMU_dt(float gx, float gy, float gz, float ax,
float ay, float az, float dt) {
float recipNorm;
float s0, s1, s2, s3;
float qDot1, qDot2, qDot3, qDot4;
float _2q0, _2q1, _2q2, _2q3, _4q0, _4q1, _4q2, _8q1, _8q2, q0q0, q1q1, q2q2,
q3q3;
// Convert gyroscope degrees/sec to radians/sec
gx *= 0.0174533f;
gy *= 0.0174533f;
gz *= 0.0174533f;
// 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))) {
// Normalise accelerometer measurement
recipNorm = Adafruit_Madgwick_invSqrt(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 = Adafruit_Madgwick_invSqrt(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 = Adafruit_Madgwick_invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
q0 *= recipNorm;
q1 *= recipNorm;
q2 *= recipNorm;
q3 *= recipNorm;
anglesComputed = 0;
}
void Adafruit_Madgwick_update(float gx, float gy, float gz, float ax, float ay,
float az, float mx, float my, float mz) {
Adafruit_Madgwick_update_dt(gx, gy, gz, ax, ay, az, mx, my, mz, invSampleFreq);
}
STATIC mp_obj_t update(size_t n_args, const mp_obj_t *args) {
// Extract the integer from the MicroPython input object
//mp_printf(&mp_plat_print, "Update nargs %d\n", n_args);
mp_float_t gx = mp_obj_get_float(args[0]);
mp_float_t gy = mp_obj_get_float(args[1]);
mp_float_t gz = mp_obj_get_float(args[2]);
mp_float_t ax = mp_obj_get_float(args[3]);
mp_float_t ay = mp_obj_get_float(args[4]);
mp_float_t az = mp_obj_get_float(args[5]);
mp_float_t mx = mp_obj_get_float(args[6]);
mp_float_t my = mp_obj_get_float(args[7]);
mp_float_t mz = mp_obj_get_float(args[8]);
Adafruit_Madgwick_update(gx,gy,gz,ax,ay,az,mx,my,mz);
return mp_const_none;
}
// Define a Python reference to the function above
STATIC MP_DEFINE_CONST_FUN_OBJ_VAR(update_obj, 9, update);
void Adafruit_Madgwick_updateIMU(float gx, float gy, float gz, float ax,
float ay, float az) {
Adafruit_Madgwick_updateIMU_dt(gx, gy, gz, ax, ay, az, invSampleFreq);
};
//-------------------------------------------------------------------------------------------
// Fast inverse square-root
// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root
float Adafruit_Madgwick_invSqrt(float x) {
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wstrict-aliasing"
float halfx = 0.5f * x;
float y = x;
long i = *(long *)&y;
i = 0x5f3759df - (i >> 1);
y = *(float *)&i;
y = y * (1.5f - (halfx * y * y));
y = y * (1.5f - (halfx * y * y));
return y;
#pragma GCC diagnostic pop
}
//-------------------------------------------------------------------------------------------
void Adafruit_Madgwick_computeAngles() {
roll = atan2f(q0 * q1 + q2 * q3, 0.5f - q1 * q1 - q2 * q2);
pitch = asinf(-2.0f * (q1 * q3 - q0 * q2));
yaw = atan2f(q1 * q2 + q0 * q3, 0.5f - q2 * q2 - q3 * q3);
grav[0] = 2.0f * (q1 * q3 - q0 * q2);
grav[1] = 2.0f * (q0 * q1 + q2 * q3);
grav[2] = 2.0f * (q1 * q0 - 0.5f + q3 * q3);
anglesComputed = 1;
}
// This is the entry point and is called when the module is imported
mp_obj_t mpy_init(mp_obj_fun_bc_t *self, size_t n_args, size_t n_kw, mp_obj_t *args) {
// This must be first, it sets up the globals dict and other things
MP_DYNRUNTIME_INIT_ENTRY
// Make the function available in the module's namespace
mp_store_global(MP_QSTR_init, MP_OBJ_FROM_PTR(&init_obj));
mp_store_global(MP_QSTR_begin, MP_OBJ_FROM_PTR(&begin_obj));
mp_store_global(MP_QSTR_update, MP_OBJ_FROM_PTR(&update_obj));
mp_store_global(MP_QSTR_getroll, MP_OBJ_FROM_PTR(&getRoll_obj));
mp_store_global(MP_QSTR_getpitch, MP_OBJ_FROM_PTR(&getPitch_obj));
mp_store_global(MP_QSTR_getyaw, MP_OBJ_FROM_PTR(&getYaw_obj));
mp_store_global(MP_QSTR_getbeta, MP_OBJ_FROM_PTR(&getBeta_obj));
mp_store_global(MP_QSTR_setbeta, MP_OBJ_FROM_PTR(&setBeta_obj));
// This must be last, it restores the globals dict
MP_DYNRUNTIME_INIT_EXIT
}
# Location of top-level MicroPython directory
MPY_DIR = ..
# Name of module
MOD = ahrs
# Source files (.c or .py)
SRC = madgwick.c ../lib/libm/ef_sqrt.c ../lib/libm/atan2f.c ../lib/libm/asinfacosf.c ../lib/libm/atanf.c
#SRC = factorial.c
# Architecture to build for (x86, x64, armv7m, xtensa, xtensawin)
ARCH = armv7emsp
# Include to get the rules for compiling and linking the module
include $(MPY_DIR)/py/dynruntime.mk
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment